Doxygen setup (#98)
* basic doxygen configuration * fix documentation: rendering, typos, etc * add main page with directory * add rmw tag files and fix file references * generate tag file * generalizing * avoid showing RCL_* function macros * remove colliding and unnecessary section
This commit is contained in:
parent
d681d29219
commit
88888fb672
22 changed files with 1708 additions and 981 deletions
1
rcl/.gitignore
vendored
Normal file
1
rcl/.gitignore
vendored
Normal file
|
@ -0,0 +1 @@
|
||||||
|
doc_output
|
27
rcl/Doxyfile
Normal file
27
rcl/Doxyfile
Normal file
|
@ -0,0 +1,27 @@
|
||||||
|
# All settings not listed here will use the Doxygen default values.
|
||||||
|
|
||||||
|
PROJECT_NAME = "rcl"
|
||||||
|
PROJECT_NUMBER = master
|
||||||
|
PROJECT_BRIEF = "C API providing common ROS client library functionality."
|
||||||
|
|
||||||
|
INPUT = ./include
|
||||||
|
RECURSIVE = YES
|
||||||
|
OUTPUT_DIRECTORY = doc_output
|
||||||
|
|
||||||
|
EXTRACT_ALL = YES
|
||||||
|
SORT_MEMBER_DOCS = NO
|
||||||
|
|
||||||
|
GENERATE_LATEX = NO
|
||||||
|
|
||||||
|
ENABLE_PREPROCESSING = YES
|
||||||
|
MACRO_EXPANSION = YES
|
||||||
|
EXPAND_ONLY_PREDEF = YES
|
||||||
|
PREDEFINED += RCL_PUBLIC=
|
||||||
|
PREDEFINED += RCL_WARN_UNUSED=
|
||||||
|
|
||||||
|
# Tag files that do not exist will produce a warning and cross-project linking will not work.
|
||||||
|
TAGFILES += "../../../../doxygen_tag_files/cppreference-doxygen-web.tag.xml=http://en.cppreference.com/w/"
|
||||||
|
# Consider changing "latest" to the version you want to reference (e.g. beta1 or 1.0.0)
|
||||||
|
TAGFILES += "../../../../doxygen_tag_files/rmw.tag=http://docs.ros2.org/latest/api/rmw/"
|
||||||
|
# Uncomment to generate tag files for cross-project linking.
|
||||||
|
#GENERATE_TAGFILE = "../../../../doxygen_tag_files/rcl.tag"
|
|
@ -25,7 +25,9 @@ extern "C"
|
||||||
#include "rcl/visibility_control.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().
|
/**
|
||||||
|
* The default allocator uses std::malloc(), std::free(), and std::realloc().
|
||||||
|
* It can be obtained using rcl_get_default_allocator().
|
||||||
*
|
*
|
||||||
* The allocator should be trivially copyable.
|
* The allocator should be trivially copyable.
|
||||||
* Meaning that the struct should continue to work after being assignment
|
* Meaning that the struct should continue to work after being assignment
|
||||||
|
@ -37,37 +39,54 @@ extern "C"
|
||||||
*/
|
*/
|
||||||
typedef struct rcl_allocator_t
|
typedef struct rcl_allocator_t
|
||||||
{
|
{
|
||||||
/// Allocate memory, given a size and state structure.
|
/// Allocate memory, given a size and the `state` pointer.
|
||||||
/* An error should be indicated by returning NULL. */
|
/** An error should be indicated by returning `NULL`. */
|
||||||
void * (*allocate)(size_t size, void * state);
|
void * (*allocate)(size_t size, void * state);
|
||||||
/// Deallocate previously allocated memory, mimicking free().
|
/// Deallocate previously allocated memory, mimicking std::free().
|
||||||
|
/** Also takes the `state` pointer. */
|
||||||
void (* deallocate)(void * pointer, void * state);
|
void (* deallocate)(void * pointer, void * state);
|
||||||
/// Reallocate if possible, otherwise it deallocates and allocates.
|
/// Reallocate if possible, otherwise it deallocates and allocates.
|
||||||
/* If unsupported then do deallocate and then allocate.
|
/**
|
||||||
* This should behave as realloc is described, as opposed to reallocf, i.e.
|
* Also takes the `state` pointer.
|
||||||
* the memory given by pointer will not be free'd automatically if realloc
|
*
|
||||||
* fails.
|
* If unsupported then do deallocate and then allocate.
|
||||||
* For reallocf behavior use rcl_reallocf().
|
* This should behave as std::realloc() does, as opposed to posix's
|
||||||
* This function must be able to take an input pointer of NULL and succeed.
|
* [reallocf](https://linux.die.net/man/3/reallocf), i.e. the memory given
|
||||||
|
* by pointer will not be free'd automatically if std::realloc() fails.
|
||||||
|
* For reallocf-like behavior use rcl_reallocf().
|
||||||
|
* This function must be able to take an input pointer of `NULL` and succeed.
|
||||||
*/
|
*/
|
||||||
void * (*reallocate)(void * pointer, size_t size, void * state);
|
void * (*reallocate)(void * pointer, size_t size, void * state);
|
||||||
/// Implementation defined state storage.
|
/// Implementation defined state storage.
|
||||||
/* This is passed as the second parameter to other allocator functions. */
|
/** This is passed as the final parameter to other allocator functions. */
|
||||||
void * state;
|
void * state;
|
||||||
} rcl_allocator_t;
|
} rcl_allocator_t;
|
||||||
|
|
||||||
/// Return a properly initialized rcl_allocator_t with default values.
|
/// Return a properly initialized rcl_allocator_t with default values.
|
||||||
/* This function does not allocate heap memory.
|
/**
|
||||||
* This function is thread-safe.
|
* This defaults to:
|
||||||
* This function is lock-free.
|
*
|
||||||
|
* - allocate = wraps std::malloc()
|
||||||
|
* - deallocate = wraps std::free()
|
||||||
|
* - reallocate = wrapps std::realloc()
|
||||||
|
* - state = `NULL`
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_allocator_t
|
rcl_allocator_t
|
||||||
rcl_get_default_allocator(void);
|
rcl_get_default_allocator(void);
|
||||||
|
|
||||||
/// Emulate the behavior of reallocf.
|
/// Emulate the behavior of [reallocf](https://linux.die.net/man/3/reallocf).
|
||||||
/* This function will return NULL if the allocator is NULL or has NULL for
|
/**
|
||||||
|
* This function will return `NULL` if the allocator is `NULL` or has `NULL` for
|
||||||
* function pointer fields.
|
* function pointer fields.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
|
|
|
@ -29,27 +29,26 @@ extern "C"
|
||||||
/// Internal rcl client implementation struct.
|
/// Internal rcl client implementation struct.
|
||||||
struct rcl_client_impl_t;
|
struct rcl_client_impl_t;
|
||||||
|
|
||||||
/// Handle for a rcl client.
|
/// Structure which encapsulates a ROS Client.
|
||||||
typedef struct rcl_client_t
|
typedef struct rcl_client_t
|
||||||
{
|
{
|
||||||
struct rcl_client_impl_t * impl;
|
struct rcl_client_impl_t * impl;
|
||||||
} rcl_client_t;
|
} rcl_client_t;
|
||||||
|
|
||||||
/// Options available for a rcl client.
|
/// Options available for a rcl_client_t.
|
||||||
typedef struct rcl_client_options_t
|
typedef struct rcl_client_options_t
|
||||||
{
|
{
|
||||||
/// Middleware quality of service settings for the client.
|
/// Middleware quality of service settings for the client.
|
||||||
rmw_qos_profile_t qos;
|
rmw_qos_profile_t qos;
|
||||||
/// Custom allocator for the client, used for incidental allocations.
|
/// Custom allocator for the client, used for incidental allocations.
|
||||||
/* For default behavior (malloc/free), use: rcl_get_default_allocator() */
|
/** For default behavior (malloc/free), use: rcl_get_default_allocator() */
|
||||||
rcl_allocator_t allocator;
|
rcl_allocator_t allocator;
|
||||||
} rcl_client_options_t;
|
} rcl_client_options_t;
|
||||||
|
|
||||||
/// Return a rcl_client_t struct with members set to NULL.
|
/// Return a rcl_client_t struct with members set to `NULL`.
|
||||||
/* Should be called to get a null rcl_client_t before passing to
|
/**
|
||||||
* rcl_initalize_client().
|
* Should be called to get a null rcl_client_t before passing to
|
||||||
* It's also possible to use calloc() instead of this if the rcl_client is
|
* rcl_client_init().
|
||||||
* being allocated on the heap.
|
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -58,40 +57,47 @@ rcl_get_zero_initialized_client(void);
|
||||||
|
|
||||||
|
|
||||||
/// Initialize a rcl client.
|
/// Initialize a rcl client.
|
||||||
/* After calling this function on a rcl_client_t, it can be used to send requests of the given
|
/**
|
||||||
* type by calling rcl_send_request().
|
* After calling this function on a rcl_client_t, it can be used to send
|
||||||
* If the request is received by a (possibly remote) service and if the service sends a response,
|
* requests of the given type by calling rcl_send_request().
|
||||||
* the client can access the response through rcl_take_response once the response is available to
|
* If the request is received by a (possibly remote) service and if the service
|
||||||
* the client.
|
* sends a response, the client can access the response through
|
||||||
|
* rcl_take_response() once the response is available to the client.
|
||||||
*
|
*
|
||||||
* The given rcl_node_t must be valid and the resulting rcl_client_t is only
|
* The given rcl_node_t must be valid and the resulting rcl_client_t is only
|
||||||
* valid as long as the given rcl_node_t remains valid.
|
* valid as long as the given rcl_node_t remains valid.
|
||||||
*
|
*
|
||||||
* The rosidl_service_type_support_t is obtained on a per .srv type basis.
|
* The rosidl_service_type_support_t is obtained on a per `.srv` type basis.
|
||||||
* When the user defines a ROS service, code is generated which provides the
|
* When the user defines a ROS service, code is generated which provides the
|
||||||
* required rosidl_service_type_support_t object.
|
* required rosidl_service_type_support_t object.
|
||||||
* This object can be obtained using a language appropriate mechanism.
|
* This object can be obtained using a language appropriate mechanism.
|
||||||
* \TODO(wjwwood) probably should talk about this once and link to it instead
|
* \todo TODO(wjwwood) write these instructions once and link to it instead
|
||||||
* For C this macro can be used (using example_interfaces/AddTwoInts as an example):
|
* For C a macro can be used (for example `example_interfaces/AddTwoInts`):
|
||||||
*
|
*
|
||||||
* #include <rosidl_generator_c/service_type_support.h>
|
* ```c
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <rosidl_generator_c/service_type_support.h>
|
||||||
* rosidl_service_type_support_t * ts =
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
* ROSIDL_GET_SERVICE_TYPE_SUPPORT(example_interfaces, AddTwoInts);
|
*
|
||||||
|
* rosidl_service_type_support_t * ts =
|
||||||
|
* ROSIDL_GET_SERVICE_TYPE_SUPPORT(example_interfaces, AddTwoInts);
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* For C++ a template function is used:
|
* For C++ a template function is used:
|
||||||
*
|
*
|
||||||
* #include <rosidl_generator_cpp/service_type_support.hpp>
|
* ```cpp
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <rosidl_generator_cpp/service_type_support.hpp>
|
||||||
* rosidl_service_type_support_t * ts = rosidl_generator_cpp::get_service_type_support_handle<
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
* example_interfaces::srv::AddTwoInts>();
|
*
|
||||||
|
* rosidl_service_type_support_t * ts =
|
||||||
|
* rosidl_generator_cpp::get_service_type_support_handle<example_interfaces::srv::AddTwoInts>();
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* The rosidl_service_type_support_t object contains service type specific
|
* The rosidl_service_type_support_t object contains service type specific
|
||||||
* information used to send or take requests and responses.
|
* information used to send or take requests and responses.
|
||||||
*
|
*
|
||||||
* \TODO(wjwwood) update this once we've come up with an official scheme.
|
* \todo TODO(wjwwood) update this once we've come up with an official scheme.
|
||||||
* The service name must be a non-empty string which follows the topic/service naming
|
* The service name must be a non-empty string which follows the topic/service
|
||||||
* format.
|
* name format conventions.
|
||||||
*
|
*
|
||||||
* The options struct allows the user to set the quality of service settings as
|
* The options struct allows the user to set the quality of service settings as
|
||||||
* well as a custom allocator which is used when initializing/finalizing the
|
* well as a custom allocator which is used when initializing/finalizing the
|
||||||
|
@ -99,38 +105,46 @@ rcl_get_zero_initialized_client(void);
|
||||||
*
|
*
|
||||||
* Expected usage (for C services):
|
* Expected usage (for C services):
|
||||||
*
|
*
|
||||||
* #include <rcl/rcl.h>
|
* ```cpp
|
||||||
* #include <rosidl_generator_c/service_type_support.h>
|
* #include <rcl/rcl.h>
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <rosidl_generator_c/service_type_support.h>
|
||||||
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
||||||
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
|
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* rosidl_service_type_support_t * ts = ROSIDL_GET_SERVICE_TYPE_SUPPORT(
|
* rosidl_service_type_support_t * ts = ROSIDL_GET_SERVICE_TYPE_SUPPORT(
|
||||||
* example_interfaces, AddTwoInts);
|
* example_interfaces, AddTwoInts);
|
||||||
* rcl_client_t client = rcl_get_zero_initialized_client();
|
* rcl_client_t client = rcl_get_zero_initialized_client();
|
||||||
* rcl_client_options_t client_ops = rcl_client_get_default_options();
|
* rcl_client_options_t client_ops = rcl_client_get_default_options();
|
||||||
* ret = rcl_client_init(&client, &node, ts, "add_two_ints", &client_ops);
|
* ret = rcl_client_init(&client, &node, ts, "add_two_ints", &client_ops);
|
||||||
* // ... error handling, and on shutdown do finalization:
|
* // ... error handling, and on shutdown do finalization:
|
||||||
* ret = rcl_client_fini(&client, &node);
|
* ret = rcl_client_fini(&client, &node);
|
||||||
* // ... error handling for rcl_client_fini()
|
* // ... error handling for rcl_client_fini()
|
||||||
* ret = rcl_node_fini(&node);
|
* ret = rcl_node_fini(&node);
|
||||||
* // ... error handling for rcl_node_fini()
|
* // ... error handling for rcl_node_fini()
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] client preallocated client structure
|
* \param[inout] client preallocated rcl_client_t structure
|
||||||
* \param[in] node valid rcl node handle
|
* \param[in] node valid rcl_node_t
|
||||||
* \param[in] type_support type support object for the service's type
|
* \param[in] type_support type support object for the service's type
|
||||||
* \param[in] service_name the name of the service to request
|
* \param[in] service_name the name of the service to request
|
||||||
* \param[in] options client options, including quality of service settings
|
* \param[in] options client options, including quality of service settings
|
||||||
* \return RCL_RET_OK if the client was initialized successfully, or
|
* \return `RCL_RET_OK` if the client was initialized successfully, or
|
||||||
* RCL_RET_NODE_INVALID if the node is invalid, or
|
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
||||||
* RCL_RET_ALREADY_INIT if the client is already initialized, or
|
* \return `RCL_RET_ALREADY_INIT` if the client is already initialized, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory fails, or
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory fails, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -143,17 +157,24 @@ rcl_client_init(
|
||||||
const rcl_client_options_t * options);
|
const rcl_client_options_t * options);
|
||||||
|
|
||||||
/// Finalize a rcl_client_t.
|
/// Finalize a rcl_client_t.
|
||||||
/*
|
/**
|
||||||
* After calling, calls to rcl_send_request and rcl_take_response will fail when using this client.
|
* After calling this function, calls to rcl_send_request() and
|
||||||
|
* rcl_take_response() will fail when using this client.
|
||||||
* However, the given node handle is still valid.
|
* However, the given node handle is still valid.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] client handle to the client to be finalized
|
* \param[inout] client handle to the client to be finalized
|
||||||
* \param[in] node handle to the node used to create the client
|
* \param[in] node handle to the node used to create the client
|
||||||
* \return RCL_RET_OK if client was finalized successfully, or
|
* \return `RCL_RET_OK` if client was finalized successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -161,43 +182,60 @@ rcl_ret_t
|
||||||
rcl_client_fini(rcl_client_t * client, rcl_node_t * node);
|
rcl_client_fini(rcl_client_t * client, rcl_node_t * node);
|
||||||
|
|
||||||
/// Return the default client options in a rcl_client_options_t.
|
/// Return the default client options in a rcl_client_options_t.
|
||||||
|
/**
|
||||||
|
* The defaults are:
|
||||||
|
*
|
||||||
|
* - qos = rmw_qos_profile_services_default
|
||||||
|
* - allocator = rcl_get_default_allocator()
|
||||||
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_client_options_t
|
rcl_client_options_t
|
||||||
rcl_client_get_default_options(void);
|
rcl_client_get_default_options(void);
|
||||||
|
|
||||||
/// Send a ROS request using a client.
|
/// Send a ROS request using a client.
|
||||||
/* It is the job of the caller to ensure that the type of the ros_request
|
/**
|
||||||
|
* It is the job of the caller to ensure that the type of the `ros_request`
|
||||||
* parameter and the type associate with the client (via the type support)
|
* parameter and the type associate with the client (via the type support)
|
||||||
* match.
|
* match.
|
||||||
* Passing a different type to send_request produces undefined behavior and cannot
|
* Passing a different type to `send_request` produces undefined behavior and
|
||||||
* be checked by this function and therefore no deliberate error will occur.
|
* cannot be checked by this function and therefore no deliberate error will
|
||||||
|
* occur.
|
||||||
*
|
*
|
||||||
* send_request is an non-blocking call.
|
* rcl_send_request() is an non-blocking call.
|
||||||
*
|
*
|
||||||
* The ROS request message given by the ros_request void pointer is always owned by the
|
* The ROS request message given by the `ros_request` void pointer is always
|
||||||
* calling code, but should remain constant during send_request.
|
* owned by the calling code, but should remain constant during `send_request`.
|
||||||
*
|
*
|
||||||
* This function is thread safe so long as access to both the client and the
|
* This function is thread safe so long as access to both the client and the
|
||||||
* ros_request is synchronized.
|
* `ros_request` is synchronized.
|
||||||
* That means that calling rcl_send_request from multiple threads is allowed, but
|
* That means that calling rcl_send_request() from multiple threads is allowed,
|
||||||
* calling rcl_send_request at the same time as non-thread safe client functions
|
* but calling rcl_send_request() at the same time as non-thread safe client
|
||||||
* is not, e.g. calling rcl_send_request and rcl_client_fini concurrently
|
* functions is not, e.g. calling rcl_send_request() and rcl_client_fini()
|
||||||
* is not allowed.
|
* concurrently is not allowed.
|
||||||
* Before calling rcl_send_request the message can change and after calling
|
* Before calling rcl_send_request() the message can change and after calling
|
||||||
* rcl_send_request the message can change, but it cannot be changed during the
|
* rcl_send_request() the message can change, but it cannot be changed during
|
||||||
* send_request call.
|
* the `send_request` call.
|
||||||
* The same ros_request, however, can be passed to multiple calls of
|
* The same `ros_request`, however, can be passed to multiple calls of
|
||||||
* rcl_send_request simultaneously, even if the clients differ.
|
* rcl_send_request() simultaneously, even if the clients differ.
|
||||||
* The ros_request is unmodified by rcl_send_request.
|
* The `ros_request` is unmodified by rcl_send_request().
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes [1]
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <i>[1] for unique pairs of clients and requests, see above for more</i>
|
||||||
*
|
*
|
||||||
* \param[in] client handle to the client which will make the response
|
* \param[in] client handle to the client which will make the response
|
||||||
* \param[in] ros_request type-erased pointer to the ROS request message
|
* \param[in] ros_request type-erased pointer to the ROS request message
|
||||||
* \param[out] sequence_number the sequence number
|
* \param[out] sequence_number the sequence number
|
||||||
* \return RCL_RET_OK if the request was sent successfully, or
|
* \return `RCL_RET_OK` if the request was sent successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_CLIENT_INVALID if the client is invalid, or
|
* \return `RCL_RET_CLIENT_INVALID` if the client is invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -205,24 +243,36 @@ rcl_ret_t
|
||||||
rcl_send_request(const rcl_client_t * client, const void * ros_request, int64_t * sequence_number);
|
rcl_send_request(const rcl_client_t * client, const void * ros_request, int64_t * sequence_number);
|
||||||
|
|
||||||
|
|
||||||
// Take a ROS response using a client
|
/// Take a ROS response using a client
|
||||||
/* It is the job of the caller to ensure that the type of the ros_response
|
/**
|
||||||
|
* It is the job of the caller to ensure that the type of the `ros_response`
|
||||||
* parameter and the type associate with the client (via the type support)
|
* parameter and the type associate with the client (via the type support)
|
||||||
* match.
|
* match.
|
||||||
* Passing a different type to take_response produces undefined behavior and cannot
|
* Passing a different type to take_response produces undefined behavior and
|
||||||
* be checked by this function and therefore no deliberate error will occur.
|
* cannot be checked by this function and therefore no deliberate error will
|
||||||
* The request_header is an rmw struct for meta-information about the request sent
|
* occur.
|
||||||
* (e.g. the sequence number).
|
* The request_header is an rmw struct for meta-information about the request
|
||||||
* ros_response should point to an already allocated ROS response message struct of the
|
* sent (e.g. the sequence number).
|
||||||
* correct type, into which the response from the service will be copied.
|
* `ros_response` should point to an already allocated ROS response message
|
||||||
|
* struct of the correct type, into which the response from the service will be
|
||||||
|
* copied.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Maybe [1]
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <i>[1] only if required when filling the message, avoided for fixed sizes</i>
|
||||||
*
|
*
|
||||||
* \param[in] client handle to the client which will take the response
|
* \param[in] client handle to the client which will take the response
|
||||||
* \param[inout] request_header pointer to the request header
|
* \param[inout] request_header pointer to the request header
|
||||||
* \param[inout] ros_response type-erased pointer to the ROS response message
|
* \param[inout] ros_response type-erased pointer to the ROS response message
|
||||||
* \return RCL_RET_OK if the response was taken successfully, or
|
* \return `RCL_RET_OK` if the response was taken successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_CLIENT_INVALID if the client is invalid, or
|
* \return `RCL_RET_CLIENT_INVALID` if the client is invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -233,19 +283,26 @@ rcl_take_response(
|
||||||
void * ros_response);
|
void * ros_response);
|
||||||
|
|
||||||
/// Get the name of the service that this client will request a response from.
|
/// Get the name of the service that this client will request a response from.
|
||||||
/* This function returns the client's internal service name string.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if the:
|
* This function returns the client's internal service name string.
|
||||||
* - client is NULL
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - client is `NULL`
|
||||||
* - client is invalid (never called init, called fini, or invalid node)
|
* - client is invalid (never called init, called fini, or invalid node)
|
||||||
*
|
*
|
||||||
* The returned string is only valid as long as the rcl_client_t is valid.
|
* The returned string is only valid as long as the rcl_client_t is valid.
|
||||||
* The value of the string may change if the service name changes, and therefore
|
* The value of the string may change if the service name changes, and therefore
|
||||||
* copying the string is recommended if this is a concern.
|
* copying the string is recommended if this is a concern.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe, and copying the result is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[in] client pointer to the client
|
* \param[in] client pointer to the client
|
||||||
* \return name string if successful, otherwise NULL
|
* \return name string if successful, otherwise `NULL`
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -253,19 +310,26 @@ const char *
|
||||||
rcl_client_get_service_name(const rcl_client_t * client);
|
rcl_client_get_service_name(const rcl_client_t * client);
|
||||||
|
|
||||||
/// Return the rcl client options.
|
/// Return the rcl client options.
|
||||||
/* This function returns the client's internal options struct.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if the:
|
* This function returns the client's internal options struct.
|
||||||
* - client is NULL
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - client is `NULL`
|
||||||
* - client is invalid (never called init, called fini, or invalid node)
|
* - client is invalid (never called init, called fini, or invalid node)
|
||||||
*
|
*
|
||||||
* The returned struct is only valid as long as the rcl_client_t is valid.
|
* The returned struct is only valid as long as the rcl_client_t is valid.
|
||||||
* The values in the struct may change if the options of the client change,
|
* The values in the struct may change if the options of the client change,
|
||||||
* and therefore copying the struct is recommended if this is a concern.
|
* and therefore copying the struct is recommended if this is a concern.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe, and copying the result is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[in] client pointer to the client
|
* \param[in] client pointer to the client
|
||||||
* \return options struct if successful, otherwise NULL
|
* \return options struct if successful, otherwise `NULL`
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -273,9 +337,10 @@ const rcl_client_options_t *
|
||||||
rcl_client_get_options(const rcl_client_t * client);
|
rcl_client_get_options(const rcl_client_t * client);
|
||||||
|
|
||||||
/// Return the rmw client handle.
|
/// Return the rmw client handle.
|
||||||
/* The handle returned is a pointer to the internally held rmw handle.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if the:
|
* The handle returned is a pointer to the internally held rmw handle.
|
||||||
* - client is NULL
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - client is `NULL`
|
||||||
* - client is invalid (never called init, called fini, or invalid node)
|
* - client is invalid (never called init, called fini, or invalid node)
|
||||||
*
|
*
|
||||||
* The returned handle is made invalid if the client is finalized or if
|
* The returned handle is made invalid if the client is finalized or if
|
||||||
|
@ -286,8 +351,16 @@ rcl_client_get_options(const rcl_client_t * client);
|
||||||
* this function each time it is needed and avoid use of the handle
|
* this function each time it is needed and avoid use of the handle
|
||||||
* concurrently with functions that might change it.
|
* concurrently with functions that might change it.
|
||||||
*
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
* \param[in] client pointer to the rcl client
|
* \param[in] client pointer to the rcl client
|
||||||
* \return rmw client handle if successful, otherwise NULL
|
* \return rmw client handle if successful, otherwise `NULL`
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
|
|
@ -33,16 +33,17 @@ extern "C"
|
||||||
typedef rmw_topic_names_and_types_t rcl_topic_names_and_types_t;
|
typedef rmw_topic_names_and_types_t rcl_topic_names_and_types_t;
|
||||||
|
|
||||||
|
|
||||||
/// Return a rcl_topic_names_and_types_t struct with members initialized to NULL.
|
/// Return a rcl_topic_names_and_types_t struct with members initialized to `NULL`.
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_topic_names_and_types_t
|
rcl_topic_names_and_types_t
|
||||||
rcl_get_zero_initialized_topic_names_and_types(void);
|
rcl_get_zero_initialized_topic_names_and_types(void);
|
||||||
|
|
||||||
/// Return a list of topic names and their types.
|
/// Return a list of topic names and their types.
|
||||||
/* This function returns a list of topic names in the ROS graph and their types.
|
/**
|
||||||
|
* This function returns a list of topic names in the ROS graph and their types.
|
||||||
*
|
*
|
||||||
* The node parameter must not be NULL, and must point to a valid node.
|
* The node parameter must not be `NULL`, and must point to a valid node.
|
||||||
*
|
*
|
||||||
* The topic_names_and_types parameter must be allocated and zero initialized.
|
* The topic_names_and_types parameter must be allocated and zero initialized.
|
||||||
* The topic_names_and_types is the output for this function, and contains
|
* The topic_names_and_types is the output for this function, and contains
|
||||||
|
@ -51,16 +52,21 @@ rcl_get_zero_initialized_topic_names_and_types(void);
|
||||||
* it is no longer needed.
|
* it is no longer needed.
|
||||||
* Failing to do so will result in leaked memory.
|
* Failing to do so will result in leaked memory.
|
||||||
*
|
*
|
||||||
* This function does manipulate heap memory.
|
* <hr>
|
||||||
* This function is not thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Maybe [1]
|
||||||
|
* <i>[1] implementation may need to protect the data structure with a lock</i>
|
||||||
*
|
*
|
||||||
* \param[in] node the handle to the node being used to query the ROS graph
|
* \param[in] node the handle to the node being used to query the ROS graph
|
||||||
* \param[out] topic_names_and_types list of topic names and their types
|
* \param[out] topic_names_and_types list of topic names and their types
|
||||||
* \return RCL_RET_OK if the query was successful, or
|
* \return `RCL_RET_OK` if the query was successful, or
|
||||||
* RCL_RET_NODE_INVALID if the node is invalid, or
|
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -70,18 +76,23 @@ rcl_get_topic_names_and_types(
|
||||||
rcl_topic_names_and_types_t * topic_names_and_types);
|
rcl_topic_names_and_types_t * topic_names_and_types);
|
||||||
|
|
||||||
/// Destroy a struct which was previously given to rcl_get_topic_names_and_types.
|
/// Destroy a struct which was previously given to rcl_get_topic_names_and_types.
|
||||||
/* The topic_names_and_types parameter must not be NULL, and must point to an
|
/**
|
||||||
|
* The topic_names_and_types parameter must not be `NULL`, and must point to an
|
||||||
* already allocated rcl_topic_names_and_types_t struct that was previously
|
* already allocated rcl_topic_names_and_types_t struct that was previously
|
||||||
* passed to a successful rcl_get_topic_names_and_types() call.
|
* passed to a successful rcl_get_topic_names_and_types() call.
|
||||||
*
|
*
|
||||||
* This function does manipulate heap memory.
|
* <hr>
|
||||||
* This function is not thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] topic_names_and_types struct to be destroyed
|
* \param[inout] topic_names_and_types struct to be destroyed
|
||||||
* \return RCL_RET_OK if successful, or
|
* \return `RCL_RET_OK` if successful, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -90,28 +101,34 @@ rcl_destroy_topic_names_and_types(
|
||||||
rcl_topic_names_and_types_t * topic_names_and_types);
|
rcl_topic_names_and_types_t * topic_names_and_types);
|
||||||
|
|
||||||
/// Return the number of publishers on a given topic.
|
/// Return the number of publishers on a given topic.
|
||||||
/* This function returns the number of publishers on a given topic.
|
/**
|
||||||
|
* This function returns the number of publishers on a given topic.
|
||||||
*
|
*
|
||||||
* The node parameter must not be NULL, and must point to a valid node.
|
* The node parameter must not be `NULL`, and must point to a valid node.
|
||||||
*
|
*
|
||||||
* The topic_name parameter must not be NULL, and must not be an empty string.
|
* The topic_name parameter must not be `NULL`, and must not be an empty string.
|
||||||
* It should also follow the topic name rules.
|
* It should also follow the topic name rules.
|
||||||
* \TODO(wjwwood): link to the topic name rules.
|
* \todo TODO(wjwwood): link to the topic name rules.
|
||||||
*
|
*
|
||||||
* The count parameter must not be NULL, and must point to a valid bool.
|
* The count parameter must not be `NULL`, and must point to a valid bool.
|
||||||
* The count parameter is the output for this function and will be set.
|
* The count parameter is the output for this function and will be set.
|
||||||
*
|
*
|
||||||
* This function may manipulate heap memory.
|
* <hr>
|
||||||
* This function is not thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Maybe [1]
|
||||||
|
* <i>[1] implementation may need to protect the data structure with a lock</i>
|
||||||
*
|
*
|
||||||
* \param[in] node the handle to the node being used to query the ROS graph
|
* \param[in] node the handle to the node being used to query the ROS graph
|
||||||
* \param[in] topic_name the name of the topic in question
|
* \param[in] topic_name the name of the topic in question
|
||||||
* \param[out] count number of publishers on the given topic
|
* \param[out] count number of publishers on the given topic
|
||||||
* \return RCL_RET_OK if the query was successful, or
|
* \return `RCL_RET_OK` if the query was successful, or
|
||||||
* RCL_RET_NODE_INVALID if the node is invalid, or
|
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -122,28 +139,34 @@ rcl_count_publishers(
|
||||||
size_t * count);
|
size_t * count);
|
||||||
|
|
||||||
/// Return the number of subscriptions on a given topic.
|
/// Return the number of subscriptions on a given topic.
|
||||||
/* This function returns the number of subscriptions on a given topic.
|
/**
|
||||||
|
* This function returns the number of subscriptions on a given topic.
|
||||||
*
|
*
|
||||||
* The node parameter must not be NULL, and must point to a valid node.
|
* The node parameter must not be `NULL`, and must point to a valid node.
|
||||||
*
|
*
|
||||||
* The topic_name parameter must not be NULL, and must not be an empty string.
|
* The topic_name parameter must not be `NULL`, and must not be an empty string.
|
||||||
* It should also follow the topic name rules.
|
* It should also follow the topic name rules.
|
||||||
* \TODO(wjwwood): link to the topic name rules.
|
* \todo TODO(wjwwood): link to the topic name rules.
|
||||||
*
|
*
|
||||||
* The count parameter must not be NULL, and must point to a valid bool.
|
* The count parameter must not be `NULL`, and must point to a valid bool.
|
||||||
* The count parameter is the output for this function and will be set.
|
* The count parameter is the output for this function and will be set.
|
||||||
*
|
*
|
||||||
* This function may manipulate heap memory.
|
* <hr>
|
||||||
* This function is not thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Maybe [1]
|
||||||
|
* <i>[1] implementation may need to protect the data structure with a lock</i>
|
||||||
*
|
*
|
||||||
* \param[in] node the handle to the node being used to query the ROS graph
|
* \param[in] node the handle to the node being used to query the ROS graph
|
||||||
* \param[in] topic_name the name of the topic in question
|
* \param[in] topic_name the name of the topic in question
|
||||||
* \param[out] count number of subscriptions on the given topic
|
* \param[out] count number of subscriptions on the given topic
|
||||||
* \return RCL_RET_OK if the query was successful, or
|
* \return `RCL_RET_OK` if the query was successful, or
|
||||||
* RCL_RET_NODE_INVALID if the node is invalid, or
|
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -154,30 +177,36 @@ rcl_count_subscribers(
|
||||||
size_t * count);
|
size_t * count);
|
||||||
|
|
||||||
/// Check if a service server is available for the given service client.
|
/// Check if a service server is available for the given service client.
|
||||||
/* This function will return true for is_available if there is a service server
|
/**
|
||||||
|
* This function will return true for is_available if there is a service server
|
||||||
* available for the given client.
|
* available for the given client.
|
||||||
*
|
*
|
||||||
* The node parameter must not be NULL, and must point to a valid node.
|
* The node parameter must not be `NULL`, and must point to a valid node.
|
||||||
*
|
*
|
||||||
* The client parameter must not be NULL, and must point to a valid client.
|
* The client parameter must not be `NULL`, and must point to a valid client.
|
||||||
*
|
*
|
||||||
* The given client and node must match, i.e. the client must have been created
|
* The given client and node must match, i.e. the client must have been created
|
||||||
* using the given node.
|
* using the given node.
|
||||||
*
|
*
|
||||||
* The is_available parameter must not be NULL, and must point a bool variable.
|
* The is_available parameter must not be `NULL`, and must point a bool variable.
|
||||||
* The result of the check will be stored in the is_available parameter.
|
* The result of the check will be stored in the is_available parameter.
|
||||||
*
|
*
|
||||||
* This function does manipulate heap memory.
|
* <hr>
|
||||||
* This function is not thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Maybe [1]
|
||||||
|
* <i>[1] implementation may need to protect the data structure with a lock</i>
|
||||||
*
|
*
|
||||||
* \param[in] node the handle to the node being used to query the ROS graph
|
* \param[in] node the handle to the node being used to query the ROS graph
|
||||||
* \param[in] client the handle to the service client being queried
|
* \param[in] client the handle to the service client being queried
|
||||||
* \param[out] is_available set to true if there is a service server available, else false
|
* \param[out] is_available set to true if there is a service server available, else false
|
||||||
* \return RCL_RET_OK if the check was made successfully (regardless of the service readiness), or
|
* \return `RCL_RET_OK` if the check was made successfully (regardless of the service readiness), or
|
||||||
* RCL_RET_NODE_INVALID if the node is invalid, or
|
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
|
|
@ -41,39 +41,47 @@ typedef struct rcl_guard_condition_options_t
|
||||||
rcl_allocator_t allocator;
|
rcl_allocator_t allocator;
|
||||||
} 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_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_guard_condition_t
|
rcl_guard_condition_t
|
||||||
rcl_get_zero_initialized_guard_condition(void);
|
rcl_get_zero_initialized_guard_condition(void);
|
||||||
|
|
||||||
/// Initialize a rcl guard_condition.
|
/// Initialize a rcl guard_condition.
|
||||||
/* After calling this function on a rcl_guard_condition_t, it can be passed to
|
/**
|
||||||
|
* After calling this function on a rcl_guard_condition_t, it can be passed to
|
||||||
* rcl_wait() and then concurrently it can be triggered to wake-up rcl_wait().
|
* rcl_wait() and then concurrently it can be triggered to wake-up rcl_wait().
|
||||||
*
|
*
|
||||||
* Expected usage:
|
* Expected usage:
|
||||||
*
|
*
|
||||||
* #include <rcl/rcl.h>
|
* ```c
|
||||||
|
* #include <rcl/rcl.h>
|
||||||
*
|
*
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition();
|
* rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition();
|
||||||
* ret = rcl_guard_condition_init(
|
* // ... customize guard condition options
|
||||||
* &guard_condition, rcl_guard_condition_get_default_options());
|
* ret = rcl_guard_condition_init(
|
||||||
* // ... error handling, and on shutdown do deinitialization:
|
* &guard_condition, rcl_guard_condition_get_default_options());
|
||||||
* ret = rcl_guard_condition_fini(&guard_condition);
|
* // ... error handling, and on shutdown do deinitialization:
|
||||||
* // ... error handling for rcl_guard_condition_fini()
|
* ret = rcl_guard_condition_fini(&guard_condition);
|
||||||
|
* // ... error handling for rcl_guard_condition_fini()
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* This function does allocate heap memory.
|
* <hr>
|
||||||
* This function is not thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] guard_condition preallocated guard_condition structure
|
* \param[inout] guard_condition preallocated guard_condition structure
|
||||||
* \param[in] options the guard_condition's options
|
* \param[in] options the guard_condition's options
|
||||||
* \return RCL_RET_OK if guard_condition was initialized successfully, or
|
* \return `RCL_RET_OK` if guard_condition was initialized successfully, or
|
||||||
* RCL_RET_ALREADY_INIT if the guard condition is already initialized, or
|
* \return `RCL_RET_ALREADY_INIT` if the guard condition is already initialized, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -83,8 +91,9 @@ rcl_guard_condition_init(
|
||||||
const rcl_guard_condition_options_t options);
|
const rcl_guard_condition_options_t options);
|
||||||
|
|
||||||
/// Same as rcl_guard_condition_init(), but reusing an existing rmw handle.
|
/// Same as rcl_guard_condition_init(), but reusing an existing rmw handle.
|
||||||
/* In addition to the documentation for rcl_guard_condition_init(), the
|
/**
|
||||||
* rmw_guard_condition parameter must not be null and must point to a valid
|
* In addition to the documentation for rcl_guard_condition_init(), the
|
||||||
|
* `rmw_guard_condition` parameter must not be `NULL` and must point to a valid
|
||||||
* rmw guard condition.
|
* rmw guard condition.
|
||||||
*
|
*
|
||||||
* Also the life time of the rcl guard condition is tied to the life time of
|
* Also the life time of the rcl guard condition is tied to the life time of
|
||||||
|
@ -95,14 +104,22 @@ rcl_guard_condition_init(
|
||||||
* Similarly if the resulting rcl guard condition is fini'ed before the rmw
|
* Similarly if the resulting rcl guard condition is fini'ed before the rmw
|
||||||
* guard condition, then the rmw guard condition is no longer valid.
|
* guard condition, then the rmw guard condition is no longer valid.
|
||||||
*
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
* \param[inout] guard_condition preallocated guard_condition structure
|
* \param[inout] guard_condition preallocated guard_condition structure
|
||||||
* \param[in] rmw_guard_condition existing rmw guard condition to reuse
|
* \param[in] rmw_guard_condition existing rmw guard condition to reuse
|
||||||
* \param[in] options the guard_condition's options
|
* \param[in] options the guard_condition's options
|
||||||
* \return RCL_RET_OK if guard_condition was initialized successfully, or
|
* \return `RCL_RET_OK` if guard_condition was initialized successfully, or
|
||||||
* RCL_RET_ALREADY_INIT if the guard condition is already initialized, or
|
* \return `RCL_RET_ALREADY_INIT` if the guard condition is already initialized, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_guard_condition_init_from_rmw(
|
rcl_guard_condition_init_from_rmw(
|
||||||
|
@ -111,17 +128,23 @@ rcl_guard_condition_init_from_rmw(
|
||||||
const rcl_guard_condition_options_t options);
|
const rcl_guard_condition_options_t options);
|
||||||
|
|
||||||
/// Finalize a rcl_guard_condition_t.
|
/// Finalize a rcl_guard_condition_t.
|
||||||
/* After calling, calls to rcl_trigger_guard_condition() will fail when using
|
/**
|
||||||
|
* After calling, calls to rcl_trigger_guard_condition() will fail when using
|
||||||
* this guard condition.
|
* this guard condition.
|
||||||
*
|
*
|
||||||
* This function does free heap memory and can allocate memory on errors.
|
* <hr>
|
||||||
* This function is not thread-safe with rcl_trigger_guard_condition().
|
* Attribute | Adherence
|
||||||
* This function is lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No [1]
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <i>[1] specifically not thread-safe with rcl_trigger_guard_condition()</i>
|
||||||
*
|
*
|
||||||
* \param[inout] guard_condition handle to the guard_condition to be finalized
|
* \param[inout] guard_condition handle to the guard_condition to be finalized
|
||||||
* \return RCL_RET_OK if guard_condition was finalized successfully, or
|
* \return `RCL_RET_OK` if guard_condition was finalized successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -129,9 +152,10 @@ rcl_ret_t
|
||||||
rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition);
|
rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition);
|
||||||
|
|
||||||
/// Return the default options in a rcl_guard_condition_options_t struct.
|
/// Return the default options in a rcl_guard_condition_options_t struct.
|
||||||
/* This function does not allocate heap memory.
|
/**
|
||||||
* This function is thread-safe.
|
* The defaults are:
|
||||||
* This function is lock-free.
|
*
|
||||||
|
* - allocator = rcl_get_default_allocator()
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -139,21 +163,26 @@ rcl_guard_condition_options_t
|
||||||
rcl_guard_condition_get_default_options(void);
|
rcl_guard_condition_get_default_options(void);
|
||||||
|
|
||||||
/// Trigger a rcl guard condition.
|
/// Trigger a rcl guard condition.
|
||||||
/* This function can fail, and return RCL_RET_INVALID_ARGUMENT, if the:
|
/**
|
||||||
* - guard condition is NULL
|
* This function can fail, and return RCL_RET_INVALID_ARGUMENT, if the:
|
||||||
|
* - guard condition is `NULL`
|
||||||
* - guard condition is invalid (never called init or called fini)
|
* - guard condition is invalid (never called init or called fini)
|
||||||
*
|
*
|
||||||
* A guard condition can be triggered from any thread.
|
* A guard condition can be triggered from any thread.
|
||||||
*
|
*
|
||||||
* This function does not allocate heap memory, but can on errors.
|
* <hr>
|
||||||
* This function is thread-safe with itself, but cannot be called concurrently
|
* Attribute | Adherence
|
||||||
* with rcl_guard_condition_fini() on the same guard condition.
|
* ------------------ | -------------
|
||||||
* This function is lock-free, but the underlying system calls may not be.
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No [1]
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <i>[1] it can be called concurrently with itself, even on the same guard condition</i>
|
||||||
*
|
*
|
||||||
* \param[in] guard_condition handle to the guard_condition to be triggered
|
* \param[in] guard_condition handle to the guard_condition to be triggered
|
||||||
* \return RCL_RET_OK if the guard condition was triggered, or
|
* \return `RCL_RET_OK` if the guard condition was triggered, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -161,9 +190,10 @@ rcl_ret_t
|
||||||
rcl_trigger_guard_condition(rcl_guard_condition_t * guard_condition);
|
rcl_trigger_guard_condition(rcl_guard_condition_t * guard_condition);
|
||||||
|
|
||||||
/// Return the rmw guard condition handle.
|
/// Return the rmw guard condition handle.
|
||||||
/* The handle returned is a pointer to the internally held rmw handle.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if the:
|
* The handle returned is a pointer to the internally held rmw handle.
|
||||||
* - guard_condition is NULL
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - guard_condition is `NULL`
|
||||||
* - guard_condition is invalid (never called init, called fini, or invalid node)
|
* - guard_condition is invalid (never called init, called fini, or invalid node)
|
||||||
*
|
*
|
||||||
* The returned handle is made invalid if the guard condition is finalized or
|
* The returned handle is made invalid if the guard condition is finalized or
|
||||||
|
@ -174,8 +204,16 @@ rcl_trigger_guard_condition(rcl_guard_condition_t * guard_condition);
|
||||||
* this function each time it is needed and avoid use of the handle
|
* this function each time it is needed and avoid use of the handle
|
||||||
* concurrently with functions that might change it.
|
* concurrently with functions that might change it.
|
||||||
*
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
* \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
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
|
|
@ -21,6 +21,7 @@ extern "C"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifndef _WIN32
|
#ifndef _WIN32
|
||||||
|
/// Ignored return values of functions with this macro will emit a warning.
|
||||||
# define RCL_WARN_UNUSED __attribute__((warn_unused_result))
|
# define RCL_WARN_UNUSED __attribute__((warn_unused_result))
|
||||||
#else
|
#else
|
||||||
# define RCL_WARN_UNUSED _Check_return_
|
# define RCL_WARN_UNUSED _Check_return_
|
||||||
|
|
|
@ -27,18 +27,20 @@ extern "C"
|
||||||
#include "rcl/types.h"
|
#include "rcl/types.h"
|
||||||
#include "rcl/visibility_control.h"
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
|
/// Constant which indicates that the default domain id should be used.
|
||||||
#define RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID SIZE_MAX
|
#define RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID SIZE_MAX
|
||||||
|
|
||||||
struct rcl_guard_condition_t;
|
struct rcl_guard_condition_t;
|
||||||
struct rcl_node_impl_t;
|
struct rcl_node_impl_t;
|
||||||
|
|
||||||
/// Handle for a ROS node.
|
/// Structure which encapsulates a ROS Node.
|
||||||
typedef struct rcl_node_t
|
typedef struct rcl_node_t
|
||||||
{
|
{
|
||||||
/// Private implementation pointer.
|
/// Private implementation pointer.
|
||||||
struct rcl_node_impl_t * impl;
|
struct rcl_node_impl_t * impl;
|
||||||
} rcl_node_t;
|
} rcl_node_t;
|
||||||
|
|
||||||
|
/// Structure which encapsulates the options for creating a rcl_node_t.
|
||||||
typedef struct rcl_node_options_t
|
typedef struct rcl_node_options_t
|
||||||
{
|
{
|
||||||
// bool anonymous_name;
|
// bool anonymous_name;
|
||||||
|
@ -46,35 +48,46 @@ typedef struct rcl_node_options_t
|
||||||
/// If true, no parameter infrastructure will be setup.
|
/// If true, no parameter infrastructure will be setup.
|
||||||
// bool no_parameters;
|
// bool no_parameters;
|
||||||
/// If set, then this value overrides the ROS_DOMAIN_ID environment variable.
|
/// If set, then this value overrides the ROS_DOMAIN_ID environment variable.
|
||||||
/* It defaults to RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID, which will cause the
|
/**
|
||||||
|
* It defaults to RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID, which will cause the
|
||||||
* node to use the ROS domain ID set in the ROS_DOMAIN_ID environment
|
* node to use the ROS domain ID set in the ROS_DOMAIN_ID environment
|
||||||
* variable, or on some systems 0 if the environment variable is not set.
|
* variable, or on some systems 0 if the environment variable is not set.
|
||||||
*
|
*
|
||||||
* \TODO(wjwwood): Should we put a limit on the ROS_DOMAIN_ID value, that way
|
* \todo TODO(wjwwood):
|
||||||
* we can have a safe value for the default
|
* Should we put a limit on the ROS_DOMAIN_ID value, that way we can have
|
||||||
* RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID? (currently max size_t)
|
* a safe value for the default RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID?
|
||||||
|
* (currently max size_t)
|
||||||
*/
|
*/
|
||||||
size_t domain_id;
|
size_t domain_id;
|
||||||
/// Custom allocator used for internal allocations.
|
/// Custom allocator used for internal allocations.
|
||||||
rcl_allocator_t allocator;
|
rcl_allocator_t allocator;
|
||||||
} 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_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_node_t
|
rcl_node_t
|
||||||
rcl_get_zero_initialized_node(void);
|
rcl_get_zero_initialized_node(void);
|
||||||
|
|
||||||
/// Initialize a ROS node.
|
/// Initialize a ROS node.
|
||||||
/* Calling this on a rcl_node_t makes it a valid node handle until rcl_shutdown
|
/**
|
||||||
|
* Calling this on a rcl_node_t makes it a valid node handle until rcl_shutdown
|
||||||
* is called or until rcl_node_fini is called on it.
|
* is called or until rcl_node_fini is called on it.
|
||||||
*
|
*
|
||||||
* After calling the ROS node object can be used to create other middleware
|
* After calling, the ROS node object can be used to create other middleware
|
||||||
* primitives like publishers, services, parameters, and etc.
|
* primitives like publishers, services, parameters, etc.
|
||||||
|
*
|
||||||
|
* \todo TODO(wjwwood): node name uniqueness is no yet enforced
|
||||||
*
|
*
|
||||||
* The name of the node cannot coincide with another node of the same name.
|
* The name of the node cannot coincide with another node of the same name.
|
||||||
* If a node of the same name is already in the domain, it will be shutdown.
|
* If a node of the same name is already in the domain, it will be shutdown.
|
||||||
*
|
*
|
||||||
|
* \todo TODO(wjwwood):
|
||||||
|
* Parameter infrastructure is currently initialized in the language specific
|
||||||
|
* client library, e.g. rclcpp for C++, but will be initialized here in the
|
||||||
|
* future. When that happens there will be an option to avoid parameter
|
||||||
|
* infrastructure with an option in the rcl_node_options_t struct.
|
||||||
|
*
|
||||||
* A node contains infrastructure for ROS parameters, which include advertising
|
* A node contains infrastructure for ROS parameters, which include advertising
|
||||||
* publishers and service servers.
|
* publishers and service servers.
|
||||||
* This function will create those external parameter interfaces even if
|
* This function will create those external parameter interfaces even if
|
||||||
|
@ -87,29 +100,36 @@ rcl_get_zero_initialized_node(void);
|
||||||
*
|
*
|
||||||
* Expected usage:
|
* Expected usage:
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* ```c
|
||||||
* rcl_node_options_t * node_ops = rcl_node_get_default_options();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
* rcl_ret_t ret = rcl_node_init(&node, "node_name", node_ops);
|
* rcl_node_options_t * node_ops = rcl_node_get_default_options();
|
||||||
* // ... error handling and then use the node, but finally deinitialize it:
|
* // ... node options customization
|
||||||
* ret = rcl_node_fini(&node);
|
* rcl_ret_t ret = rcl_node_init(&node, "node_name", node_ops);
|
||||||
* // ... error handling for rcl_node_fini()
|
* // ... error handling and then use the node, but eventually deinitialize it:
|
||||||
|
* ret = rcl_node_fini(&node);
|
||||||
|
* // ... error handling for rcl_node_fini()
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* This function allocates heap memory.
|
* <hr>
|
||||||
* This function is not thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* ------------------ | -------------
|
||||||
* atomic_is_lock_free() returns true for atomic_uint_least64_t.
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \pre the node handle must be allocated, zero initialized, and invalid
|
* \pre the node handle must be allocated, zero initialized, and invalid
|
||||||
* \post the node handle is valid and can be used to in other rcl_* functions
|
* \post the node handle is valid and can be used in other `rcl_*` functions
|
||||||
*
|
*
|
||||||
* \param[inout] node a preallocated node structure
|
* \param[inout] node a preallocated rcl_node_t
|
||||||
* \param[in] name the name of the node
|
* \param[in] name the name of the node
|
||||||
* \param[in] options the node options; pass null to use default options
|
* \param[in] options the node options
|
||||||
* \return RCL_RET_OK if node was initialized successfully, or
|
* \return `RCL_RET_OK` if the node was initialized successfully, or
|
||||||
* RCL_RET_ALREADY_INIT if the node has already be initialized, or
|
* \return `RCL_RET_ALREADY_INIT` if the node has already be initialized, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -117,21 +137,26 @@ 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);
|
||||||
|
|
||||||
/// Finalized a rcl_node_t.
|
/// Finalized a rcl_node_t.
|
||||||
/* Shuts down any automatically created infrastructure and deallocates memory.
|
/**
|
||||||
|
* Destroys any automatically created infrastructure and deallocates memory.
|
||||||
* After calling, the rcl_node_t can be safely deallocated.
|
* After calling, the rcl_node_t can be safely deallocated.
|
||||||
*
|
*
|
||||||
* Any middleware primitives created by the user, e.g. publishers, services, etc.,
|
* Any middleware primitives created by the user, e.g. publishers, services, etc.,
|
||||||
* are invalid after deinitialization.
|
* are invalid after deinitialization.
|
||||||
*
|
*
|
||||||
* This function manipulates heap memory.
|
* <hr>
|
||||||
* This function is not thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* ------------------ | -------------
|
||||||
* atomic_is_lock_free() returns true for atomic_uint_least64_t.
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \param[in] node handle to the node to be finalized
|
* \param[in] node rcl_node_t to be finalized
|
||||||
* \return RCL_RET_OK if node was finalized successfully, or
|
* \return `RCL_RET_OK` if node was finalized successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -139,57 +164,76 @@ 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.
|
||||||
|
/**
|
||||||
|
* The default values are:
|
||||||
|
*
|
||||||
|
* - domain_id = RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID
|
||||||
|
* - allocator = rcl_get_default_allocator()
|
||||||
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
rcl_node_options_t
|
rcl_node_options_t
|
||||||
rcl_node_get_default_options(void);
|
rcl_node_get_default_options(void);
|
||||||
|
|
||||||
/// Return true if the node is valid, else false.
|
/// Return `true` if the node is valid, else `false`.
|
||||||
/* Also return false if the node pointer is nullptr.
|
/**
|
||||||
|
* Also return `false` if the node pointer is `NULL`.
|
||||||
*
|
*
|
||||||
* A node is invalid if:
|
* A node is invalid if:
|
||||||
* - the implementation is null (rcl_node_init not called or failed)
|
* - the implementation is `NULL` (rcl_node_init not called or failed)
|
||||||
* - rcl_shutdown has been called since the node has been initialized
|
* - rcl_shutdown has been called since the node has been initialized
|
||||||
* - the node has been finalized with rcl_node_fini
|
* - the node has been finalized with rcl_node_fini
|
||||||
*
|
*
|
||||||
* There is a possible validity race condition.
|
* There is a possible validity race condition.
|
||||||
|
*
|
||||||
* Consider:
|
* Consider:
|
||||||
*
|
*
|
||||||
* assert(rcl_node_is_valid(node)); <-- thread 1
|
* ```c
|
||||||
* rcl_shutdown(); <-- thread 2
|
* assert(rcl_node_is_valid(node)); // <-- thread 1
|
||||||
* // use node as if valid <-- thread 1
|
* rcl_shutdown(); // <-- thread 2
|
||||||
|
* // use node as if valid // <-- thread 1
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* In the third line the node is now invalid, even though on the previous line
|
* In the third line the node is now invalid, even though on the previous line
|
||||||
* of thread 1 it was checked to be valid.
|
* of thread 1 it was checked to be valid.
|
||||||
* This is why this function is considered not thread-safe.
|
* This is why this function is considered not thread-safe.
|
||||||
*
|
*
|
||||||
* This function does not manipulate heap memory.
|
* <hr>
|
||||||
* This function is not thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* ------------------ | -------------
|
||||||
* atomic_is_lock_free() returns true for atomic_uint_least64_t.
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \param[in] node handle to the node to validated
|
* \param[in] node rcl_node_t to be validated
|
||||||
* \return true if the node is valid, otherwise false.
|
* \return `true` if the node is valid, otherwise `false`.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
bool
|
bool
|
||||||
rcl_node_is_valid(const rcl_node_t * node);
|
rcl_node_is_valid(const rcl_node_t * node);
|
||||||
|
|
||||||
/// Get the name of the node.
|
/// Return the name of the node.
|
||||||
/* This function returns the node's internal name string.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if:
|
* This function returns the node's internal name string.
|
||||||
* - node is NULL
|
* This function can fail, and therefore return `NULL`, if:
|
||||||
|
* - node is `NULL`
|
||||||
* - node has not been initialized (the implementation is invalid)
|
* - node has not been initialized (the implementation is invalid)
|
||||||
*
|
*
|
||||||
* The returned string is only valid as long as the given rcl_node_t is valid.
|
* The returned string is only valid as long as the given rcl_node_t is valid.
|
||||||
* The value of the string may change if the value in the rcl_node_t changes,
|
* The value of the string may change if the value in the rcl_node_t changes,
|
||||||
* and therefore copying the string is recommended if this is a concern.
|
* and therefore copying the string is recommended if this is a concern.
|
||||||
*
|
*
|
||||||
* This function does not manipulate heap memory.
|
* <hr>
|
||||||
* This function is thread-safe for different nodes.
|
* Attribute | Adherence
|
||||||
* This function is lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \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
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -197,21 +241,26 @@ const char *
|
||||||
rcl_node_get_name(const rcl_node_t * node);
|
rcl_node_get_name(const rcl_node_t * node);
|
||||||
|
|
||||||
/// Return the rcl node options.
|
/// Return the rcl node options.
|
||||||
/* This function returns the node's internal options struct.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if:
|
* This function returns the node's internal options struct.
|
||||||
* - node is NULL
|
* This function can fail, and therefore return `NULL`, if:
|
||||||
|
* - node is `NULL`
|
||||||
* - node has not been initialized (the implementation is invalid)
|
* - node has not been initialized (the implementation is invalid)
|
||||||
*
|
*
|
||||||
* The returned struct is only valid as long as the given rcl_node_t is valid.
|
* The returned struct is only valid as long as the given rcl_node_t is valid.
|
||||||
* The values in the struct may change if the options of the rcl_node_t changes,
|
* The values in the struct may change if the options of the rcl_node_t changes,
|
||||||
* and therefore copying the struct is recommended if this is a concern.
|
* and therefore copying the struct is recommended if this is a concern.
|
||||||
*
|
*
|
||||||
* This function does not manipulate heap memory.
|
* <hr>
|
||||||
* This function is thread-safe for different nodes.
|
* Attribute | Adherence
|
||||||
* This function is lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \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
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -219,26 +268,32 @@ const rcl_node_options_t *
|
||||||
rcl_node_get_options(const rcl_node_t * node);
|
rcl_node_get_options(const rcl_node_t * node);
|
||||||
|
|
||||||
/// Return the ROS domain ID that the node is using.
|
/// Return the ROS domain ID that the node is using.
|
||||||
/* This function returns the ROS domain ID that the node is in.
|
/**
|
||||||
|
* This function returns the ROS domain ID that the node is in.
|
||||||
*
|
*
|
||||||
* This function should be used to determine what domain_id was used rather
|
* This function should be used to determine what `domain_id` was used rather
|
||||||
* than checking the domin_id field in the node options, because if
|
* than checking the domin_id field in the node options, because if
|
||||||
* RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID is used when creating the node then
|
* `RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID` is used when creating the node then
|
||||||
* it is not changed after creation, but this function will return the actual
|
* it is not changed after creation, but this function will return the actual
|
||||||
* domain_id used.
|
* `domain_id` used.
|
||||||
*
|
*
|
||||||
* The domain_id field must point to an allocated size_t object to which the
|
* The `domain_id` field must point to an allocated `size_t` object to which
|
||||||
* ROS domain ID will be written.
|
* the ROS domain ID will be written.
|
||||||
*
|
*
|
||||||
* This function does not manipulate heap memory.
|
* <hr>
|
||||||
* This function is thread-safe for different nodes.
|
* Attribute | Adherence
|
||||||
* This function is lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[in] node the handle to the node being queried
|
* \param[in] node the handle to the node being queried
|
||||||
* \return RCL_RET_OK if node the domain ID was retrieved successfully, or
|
* \param[out] domain_id storage for the domain id
|
||||||
* RCL_RET_NODE_INVALID if the node is invalid, or
|
* \return `RCL_RET_OK` if node the domain ID was retrieved successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -246,9 +301,10 @@ 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);
|
||||||
|
|
||||||
/// Return the rmw node handle.
|
/// Return the rmw node handle.
|
||||||
/* The handle returned is a pointer to the internally held rmw handle.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if:
|
* The handle returned is a pointer to the internally held rmw handle.
|
||||||
* - node is NULL
|
* This function can fail, and therefore return `NULL`, if:
|
||||||
|
* - node is `NULL`
|
||||||
* - node has not been initialized (the implementation is invalid)
|
* - node has not been initialized (the implementation is invalid)
|
||||||
*
|
*
|
||||||
* The returned handle is made invalid if the node is finalized or if
|
* The returned handle is made invalid if the node is finalized or if
|
||||||
|
@ -259,12 +315,16 @@ rcl_node_get_domain_id(const rcl_node_t * node, size_t * domain_id);
|
||||||
* this function each time it is needed and avoid use of the handle
|
* this function each time it is needed and avoid use of the handle
|
||||||
* concurrently with functions that might change it.
|
* concurrently with functions that might change it.
|
||||||
*
|
*
|
||||||
* This function does not manipulate heap memory.
|
* <hr>
|
||||||
* This function is thread-safe for different nodes.
|
* Attribute | Adherence
|
||||||
* This function is lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \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
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -272,23 +332,28 @@ rmw_node_t *
|
||||||
rcl_node_get_rmw_handle(const rcl_node_t * node);
|
rcl_node_get_rmw_handle(const rcl_node_t * node);
|
||||||
|
|
||||||
/// Return the associated rcl instance id.
|
/// Return the associated rcl instance id.
|
||||||
/* This id is stored when rcl_node_init is called and can be compared with the
|
/**
|
||||||
|
* This id is stored when rcl_node_init is called and can be compared with the
|
||||||
* value returned by rcl_get_instance_id() to check if this node was created in
|
* value returned by rcl_get_instance_id() to check if this node was created in
|
||||||
* the current rcl context (since the latest call to rcl_init().
|
* the current rcl context (since the latest call to rcl_init().
|
||||||
*
|
*
|
||||||
* This function can fail, and therefore return 0, if:
|
* This function can fail, and therefore return `0`, if:
|
||||||
* - node is NULL
|
* - node is `NULL`
|
||||||
* - node has not been initialized (the implementation is invalid)
|
* - node has not been initialized (the implementation is invalid)
|
||||||
*
|
*
|
||||||
* This function will succeed, however, even if rcl_shutdown has been called
|
* This function will succeed even if rcl_shutdown() has been called
|
||||||
* since the node was created.
|
* since the node was created.
|
||||||
*
|
*
|
||||||
* This function does not manipulate heap memory.
|
* <hr>
|
||||||
* This function is thread-safe for different nodes.
|
* Attribute | Adherence
|
||||||
* This function is lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \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 during node init or `0` on error
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -296,9 +361,10 @@ uint64_t
|
||||||
rcl_node_get_rcl_instance_id(const rcl_node_t * node);
|
rcl_node_get_rcl_instance_id(const rcl_node_t * node);
|
||||||
|
|
||||||
/// Return a guard condition which is triggered when the ROS graph changes.
|
/// Return a guard condition which is triggered when the ROS graph changes.
|
||||||
/* The handle returned is a pointer to an internally held rcl guard condition.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if:
|
* The handle returned is a pointer to an internally held rcl guard condition.
|
||||||
* - node is NULL
|
* This function can fail, and therefore return `NULL`, if:
|
||||||
|
* - node is `NULL`
|
||||||
* - node is invalid
|
* - node is invalid
|
||||||
*
|
*
|
||||||
* The returned handle is made invalid if the node is finialized or if
|
* The returned handle is made invalid if the node is finialized or if
|
||||||
|
@ -309,13 +375,18 @@ rcl_node_get_rcl_instance_id(const rcl_node_t * node);
|
||||||
* advertises, a new subscription is created, a new service becomes available,
|
* advertises, a new subscription is created, a new service becomes available,
|
||||||
* a subscription is canceled, etc.
|
* a subscription is canceled, etc.
|
||||||
*
|
*
|
||||||
* This function does not manipulate heap memory.
|
* \todo TODO(wjwwood): link to exhaustive list of graph events
|
||||||
* This function is thread-safe.
|
*
|
||||||
* This function is lock-free.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[in] node pointer to the rcl node
|
* \param[in] node pointer to the rcl node
|
||||||
* \return rcl guard condition handle if successful, otherwise NULL
|
* \return rcl guard condition handle if successful, otherwise `NULL`
|
||||||
*
|
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
|
|
@ -29,7 +29,7 @@ extern "C"
|
||||||
/// Internal rcl publisher implementation struct.
|
/// Internal rcl publisher implementation struct.
|
||||||
struct rcl_publisher_impl_t;
|
struct rcl_publisher_impl_t;
|
||||||
|
|
||||||
/// Handle for a rcl publisher.
|
/// Structure which encapsulates a ROS Publisher.
|
||||||
typedef struct rcl_publisher_t
|
typedef struct rcl_publisher_t
|
||||||
{
|
{
|
||||||
struct rcl_publisher_impl_t * impl;
|
struct rcl_publisher_impl_t * impl;
|
||||||
|
@ -41,15 +41,14 @@ typedef struct rcl_publisher_options_t
|
||||||
/// Middleware quality of service settings for the publisher.
|
/// Middleware quality of service settings for the publisher.
|
||||||
rmw_qos_profile_t qos;
|
rmw_qos_profile_t qos;
|
||||||
/// Custom allocator for the publisher, used for incidental allocations.
|
/// Custom allocator for the publisher, used for incidental allocations.
|
||||||
/* For default behavior (malloc/free), use: rcl_get_default_allocator() */
|
/** For default behavior (malloc/free), use: rcl_get_default_allocator() */
|
||||||
rcl_allocator_t allocator;
|
rcl_allocator_t allocator;
|
||||||
} rcl_publisher_options_t;
|
} rcl_publisher_options_t;
|
||||||
|
|
||||||
/// Return a rcl_publisher_t struct with members set to NULL.
|
/// Return a rcl_publisher_t struct with members set to `NULL`.
|
||||||
/* Should be called to get a null rcl_publisher_t before passing to
|
/**
|
||||||
* rcl_initalize_publisher().
|
* Should be called to get a null rcl_publisher_t before passing to
|
||||||
* It's also possible to use calloc() instead of this if the rcl_publisher is
|
* rcl_publisher_init().
|
||||||
* being allocated on the heap.
|
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -57,7 +56,8 @@ rcl_publisher_t
|
||||||
rcl_get_zero_initialized_publisher(void);
|
rcl_get_zero_initialized_publisher(void);
|
||||||
|
|
||||||
/// Initialize a rcl publisher.
|
/// Initialize a rcl publisher.
|
||||||
/* After calling this function on a rcl_publisher_t, it can be used to publish
|
/**
|
||||||
|
* After calling this function on a rcl_publisher_t, it can be used to publish
|
||||||
* messages of the given type to the given topic using rcl_publish().
|
* messages of the given type to the given topic using rcl_publish().
|
||||||
*
|
*
|
||||||
* The given rcl_node_t must be valid and the resulting rcl_publisher_t is only
|
* The given rcl_node_t must be valid and the resulting rcl_publisher_t is only
|
||||||
|
@ -67,25 +67,29 @@ rcl_get_zero_initialized_publisher(void);
|
||||||
* When the user defines a ROS message, code is generated which provides the
|
* When the user defines a ROS message, code is generated which provides the
|
||||||
* required rosidl_message_type_support_t object.
|
* required rosidl_message_type_support_t object.
|
||||||
* This object can be obtained using a language appropriate mechanism.
|
* This object can be obtained using a language appropriate mechanism.
|
||||||
* \TODO(wjwwood) probably should talk about this once and link to it instead
|
* \todo TODO(wjwwood) write these instructions once and link to it instead
|
||||||
* For C this macro can be used (using std_msgs/String as an example):
|
* For C a macro can be used (for example `std_msgs/String`):
|
||||||
*
|
*
|
||||||
* #include <rosidl_generator_c/message_type_support.h>
|
* ```c
|
||||||
* #include <std_msgs/msgs/string.h>
|
* #include <rosidl_generator_c/message_type_support.h>
|
||||||
* rosidl_message_type_support_t * string_ts =
|
* #include <std_msgs/msgs/string.h>
|
||||||
* ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
|
* rosidl_message_type_support_t * string_ts =
|
||||||
|
* ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* For C++ a template function is used:
|
* For C++ a template function is used:
|
||||||
*
|
*
|
||||||
* #include <rosidl_generator_cpp/message_type_support.hpp>
|
* ```cpp
|
||||||
* #include <std_msgs/msgs/string.hpp>
|
* #include <rosidl_generator_cpp/message_type_support.hpp>
|
||||||
* rosidl_message_type_support_t * string_ts =
|
* #include <std_msgs/msgs/string.hpp>
|
||||||
* rosidl_generator_cpp::get_message_type_support_handle<std_msgs::msg::String>();
|
* rosidl_message_type_support_t * string_ts =
|
||||||
|
* rosidl_generator_cpp::get_message_type_support_handle<std_msgs::msg::String>();
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* The rosidl_message_type_support_t object contains message type specific
|
* The rosidl_message_type_support_t object contains message type specific
|
||||||
* information used to publish messages.
|
* information used to publish messages.
|
||||||
*
|
*
|
||||||
* \TODO(wjwwood) update this once we've come up with an official scheme.
|
* \todo TODO(wjwwood) update this once we've come up with an official scheme.
|
||||||
* The topic name must be a non-empty string which follows the topic naming
|
* The topic name must be a non-empty string which follows the topic naming
|
||||||
* format.
|
* format.
|
||||||
*
|
*
|
||||||
|
@ -95,37 +99,45 @@ rcl_get_zero_initialized_publisher(void);
|
||||||
*
|
*
|
||||||
* Expected usage (for C messages):
|
* Expected usage (for C messages):
|
||||||
*
|
*
|
||||||
* #include <rcl/rcl.h>
|
* ```c
|
||||||
* #include <rosidl_generator_c/message_type_support.h>
|
* #include <rcl/rcl.h>
|
||||||
* #include <std_msgs/msgs/string.h>
|
* #include <rosidl_generator_c/message_type_support.h>
|
||||||
|
* #include <std_msgs/msgs/string.h>
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
||||||
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
|
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* rosidl_message_type_support_t * ts = ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
|
* rosidl_message_type_support_t * ts = ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
|
||||||
* rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
* rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
||||||
* rcl_publisher_options_t publisher_ops = rcl_publisher_get_default_options();
|
* rcl_publisher_options_t publisher_ops = rcl_publisher_get_default_options();
|
||||||
* ret = rcl_publisher_init(&publisher, &node, ts, "chatter", &publisher_ops);
|
* ret = rcl_publisher_init(&publisher, &node, ts, "chatter", &publisher_ops);
|
||||||
* // ... error handling, and on shutdown do finalization:
|
* // ... error handling, and on shutdown do finalization:
|
||||||
* ret = rcl_publisher_fini(&publisher, &node);
|
* ret = rcl_publisher_fini(&publisher, &node);
|
||||||
* // ... error handling for rcl_publisher_fini()
|
* // ... error handling for rcl_publisher_fini()
|
||||||
* ret = rcl_node_fini(&node);
|
* ret = rcl_node_fini(&node);
|
||||||
* // ... error handling for rcl_deinitialize_node()
|
* // ... error handling for rcl_deinitialize_node()
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] publisher preallocated publisher structure
|
* \param[inout] publisher preallocated publisher structure
|
||||||
* \param[in] node valid rcl node handle
|
* \param[in] node valid rcl node handle
|
||||||
* \param[in] type_support type support object for the topic's type
|
* \param[in] type_support type support object for the topic's type
|
||||||
* \param[in] topic_name the name of the topic to publish on
|
* \param[in] topic_name the name of the topic to publish on
|
||||||
* \param[in] options publisher options, including quality of service settings
|
* \param[in] options publisher options, including quality of service settings
|
||||||
* \return RCL_RET_OK if the publisher was initialized successfully, or
|
* \return `RCL_RET_OK` if the publisher was initialized successfully, or
|
||||||
* RCL_RET_NODE_INVALID if the node is invalid, or
|
* \return `RCL_RET_NODE_INVALID` if the node is invalid, or
|
||||||
* RCL_RET_ALREADY_INIT if the publisher is already initialized, or
|
* \return `RCL_RET_ALREADY_INIT` if the publisher is already initialized, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory fails, or
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory fails, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -138,19 +150,26 @@ rcl_publisher_init(
|
||||||
const rcl_publisher_options_t * options);
|
const rcl_publisher_options_t * options);
|
||||||
|
|
||||||
/// Finalize a rcl_publisher_t.
|
/// Finalize a rcl_publisher_t.
|
||||||
/* After calling, the node will no longer be advertising that it is publishing
|
/**
|
||||||
|
* After calling, the node will no longer be advertising that it is publishing
|
||||||
* on this topic (assuming this is the only publisher on this topic).
|
* on this topic (assuming this is the only publisher on this topic).
|
||||||
*
|
*
|
||||||
* After calling, calls to rcl_publish will fail when using this publisher.
|
* After calling, calls to rcl_publish will fail when using this publisher.
|
||||||
* However, the given node handle is still valid.
|
* However, the given node handle is still valid.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] publisher handle to the publisher to be finalized
|
* \param[inout] publisher handle to the publisher to be finalized
|
||||||
* \param[in] node handle to the node used to create the publisher
|
* \param[in] node handle to the node used to create the publisher
|
||||||
* \return RCL_RET_OK if publisher was finalized successfully, or
|
* \return `RCL_RET_OK` if publisher was finalized successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -158,23 +177,32 @@ 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.
|
||||||
|
/**
|
||||||
|
* The defaults are:
|
||||||
|
*
|
||||||
|
* - qos = rmw_qos_profile_default
|
||||||
|
* - allocator = rcl_get_default_allocator()
|
||||||
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_publisher_options_t
|
rcl_publisher_options_t
|
||||||
rcl_publisher_get_default_options(void);
|
rcl_publisher_get_default_options(void);
|
||||||
|
|
||||||
/// Publish a ROS message on a topic using a publisher.
|
/// Publish a ROS message on a topic using a publisher.
|
||||||
/* It is the job of the caller to ensure that the type of the ros_message
|
/**
|
||||||
|
* It is the job of the caller to ensure that the type of the ros_message
|
||||||
* parameter and the type associate with the publisher (via the type support)
|
* parameter and the type associate with the publisher (via the type support)
|
||||||
* match.
|
* match.
|
||||||
* Passing a different type to publish produces undefined behavior and cannot
|
* Passing a different type to publish produces undefined behavior and cannot
|
||||||
* be checked by this function and therefore no deliberate error will occur.
|
* be checked by this function and therefore no deliberate error will occur.
|
||||||
*
|
*
|
||||||
* TODO(wjwwood): update after researching what the blocking behavior is
|
* \todo TODO(wjwwood):
|
||||||
* or optionally link to a document that describes blocking
|
* The blocking behavior of publish is a still a point of dispute.
|
||||||
* behavior is more detail.
|
* This section should be updated once the behavior is clearly defined.
|
||||||
* Calling rcl_publish is a potentially blocking call.
|
* See: https://github.com/ros2/ros2/issues/255
|
||||||
* When called rcl_publish will immediately do any publishing related work,
|
*
|
||||||
|
* Calling rcl_publish() is a potentially blocking call.
|
||||||
|
* When called rcl_publish() will immediately do any publishing related work,
|
||||||
* including, but not limited to, converting the message into a different type,
|
* including, but not limited to, converting the message into a different type,
|
||||||
* serializing the message, collecting publish statistics, etc.
|
* serializing the message, collecting publish statistics, etc.
|
||||||
* The last thing it will do is call the underlying middleware's publish
|
* The last thing it will do is call the underlying middleware's publish
|
||||||
|
@ -184,28 +212,37 @@ rcl_publisher_get_default_options(void);
|
||||||
* until space in the publish queue is available, but if the reliability is set
|
* until space in the publish queue is available, but if the reliability is set
|
||||||
* to best effort then it should not block.
|
* to best effort then it should not block.
|
||||||
*
|
*
|
||||||
* The ROS message given by the ros_message void pointer is always owned by the
|
* The ROS message given by the `ros_message` void pointer is always owned by
|
||||||
* calling code, but should remain constant during publish.
|
* the calling code, but should remain constant during publish.
|
||||||
*
|
*
|
||||||
* This function is thread safe so long as access to both the publisher and the
|
* This function is thread safe so long as access to both the publisher and the
|
||||||
* ros_message is synchronized.
|
* `ros_message` is synchronized.
|
||||||
* That means that calling rcl_publish from multiple threads is allowed, but
|
* That means that calling rcl_publish() from multiple threads is allowed, but
|
||||||
* calling rcl_publish at the same time as non-thread safe publisher functions
|
* calling rcl_publish() at the same time as non-thread safe publisher
|
||||||
* is not, e.g. calling rcl_publish and rcl_publisher_fini concurrently
|
* functions is not, e.g. calling rcl_publish() and rcl_publisher_fini()
|
||||||
* is not allowed.
|
* concurrently is not allowed.
|
||||||
* Before calling rcl_publish the message can change and after calling
|
* Before calling rcl_publish() the message can change and after calling
|
||||||
* rcl_publish the message can change, but it cannot be changed during the
|
* rcl_publish() the message can change, but it cannot be changed during the
|
||||||
* publish call.
|
* publish call.
|
||||||
* The same ros_message, however, can be passed to multiple calls of
|
* The same `ros_message`, however, can be passed to multiple calls of
|
||||||
* rcl_publish simultaneously, even if the publishers differ.
|
* rcl_publish() simultaneously, even if the publishers differ.
|
||||||
* The ros_message is unmodified by rcl_publish.
|
* The `ros_message` is unmodified by rcl_publish().
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes [1]
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <i>[1] for unique pairs of publishers and messages, see above for more</i>
|
||||||
*
|
*
|
||||||
* \param[in] publisher handle to the publisher which will do the publishing
|
* \param[in] publisher handle to the publisher which will do the publishing
|
||||||
* \param[in] ros_message type-erased pointer to the ROS message
|
* \param[in] ros_message type-erased pointer to the ROS message
|
||||||
* \return RCL_RET_OK if the message was published successfully, or
|
* \return `RCL_RET_OK` if the message was published successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_PUBLISHER_INVALID if the publisher is invalid, or
|
* \return `RCL_RET_PUBLISHER_INVALID` if the publisher is invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -213,19 +250,26 @@ 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);
|
||||||
|
|
||||||
/// Get the topic name for the publisher.
|
/// Get the topic name for the publisher.
|
||||||
/* This function returns the publisher's internal topic name string.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if the:
|
* This function returns the publisher's internal topic name string.
|
||||||
* - publisher is NULL
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - publisher is `NULL`
|
||||||
* - publisher is invalid (never called init, called fini, or invalid node)
|
* - publisher is invalid (never called init, called fini, or invalid node)
|
||||||
*
|
*
|
||||||
* The returned string is only valid as long as the rcl_publisher_t is valid.
|
* The returned string is only valid as long as the rcl_publisher_t is valid.
|
||||||
* The value of the string may change if the topic name changes, and therefore
|
* The value of the string may change if the topic name changes, and therefore
|
||||||
* copying the string is recommended if this is a concern.
|
* copying the string is recommended if this is a concern.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe, and copying the result is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \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
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -233,19 +277,26 @@ const char *
|
||||||
rcl_publisher_get_topic_name(const rcl_publisher_t * publisher);
|
rcl_publisher_get_topic_name(const rcl_publisher_t * publisher);
|
||||||
|
|
||||||
/// Return the rcl publisher options.
|
/// Return the rcl publisher options.
|
||||||
/* This function returns the publisher's internal options struct.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if the:
|
* This function returns the publisher's internal options struct.
|
||||||
* - publisher is NULL
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - publisher is `NULL`
|
||||||
* - publisher is invalid (never called init, called fini, or invalid node)
|
* - publisher is invalid (never called init, called fini, or invalid node)
|
||||||
*
|
*
|
||||||
* The returned struct is only valid as long as the rcl_publisher_t is valid.
|
* The returned struct is only valid as long as the rcl_publisher_t is valid.
|
||||||
* The values in the struct may change if the options of the publisher change,
|
* The values in the struct may change if the options of the publisher change,
|
||||||
* and therefore copying the struct is recommended if this is a concern.
|
* and therefore copying the struct is recommended if this is a concern.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe, and copying the result is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \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
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -253,9 +304,10 @@ const rcl_publisher_options_t *
|
||||||
rcl_publisher_get_options(const rcl_publisher_t * publisher);
|
rcl_publisher_get_options(const rcl_publisher_t * publisher);
|
||||||
|
|
||||||
/// Return the rmw publisher handle.
|
/// Return the rmw publisher handle.
|
||||||
/* The handle returned is a pointer to the internally held rmw handle.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if the:
|
* The handle returned is a pointer to the internally held rmw handle.
|
||||||
* - publisher is NULL
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - publisher is `NULL`
|
||||||
* - publisher is invalid (never called init, called fini, or invalid node)
|
* - publisher is invalid (never called init, called fini, or invalid node)
|
||||||
*
|
*
|
||||||
* The returned handle is made invalid if the publisher is finalized or if
|
* The returned handle is made invalid if the publisher is finalized or if
|
||||||
|
@ -266,8 +318,16 @@ rcl_publisher_get_options(const rcl_publisher_t * publisher);
|
||||||
* this function each time it is needed and avoid use of the handle
|
* this function each time it is needed and avoid use of the handle
|
||||||
* concurrently with functions that might change it.
|
* concurrently with functions that might change it.
|
||||||
*
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
*
|
||||||
* \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
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
|
|
@ -12,6 +12,50 @@
|
||||||
// See the License for the specific language governing permissions and
|
// See the License for the specific language governing permissions and
|
||||||
// limitations under the License.
|
// limitations under the License.
|
||||||
|
|
||||||
|
/** \mainpage rcl: Common functionality for other ROS Client Libraries
|
||||||
|
*
|
||||||
|
* `rcl` consists of functions and structs (pure C) organized into ROS concepts:
|
||||||
|
*
|
||||||
|
* - Nodes
|
||||||
|
* - rcl/node.h
|
||||||
|
* - Publisher
|
||||||
|
* - rcl/publisher.h
|
||||||
|
* - Subscription
|
||||||
|
* - rcl/subscription.h
|
||||||
|
* - Service Client
|
||||||
|
* - rcl/client.h
|
||||||
|
* - Service Server
|
||||||
|
* - rcl/service.h
|
||||||
|
* - Timer
|
||||||
|
* - rcl/timer.h
|
||||||
|
*
|
||||||
|
* It also has some machinery that is necessary to wait on and act on these concepts:
|
||||||
|
*
|
||||||
|
* - Initialization and shutdown management (global for now)
|
||||||
|
* - rcl/rcl.h
|
||||||
|
* - Wait sets for waiting on messages/service requests and responses/timers to be ready
|
||||||
|
* - rcl/wait.h
|
||||||
|
* - Guard conditions for waking up wait sets asynchronously
|
||||||
|
* - rcl/guard_condition.h
|
||||||
|
* - Functions for introspecting and getting notified of changes of the ROS graph
|
||||||
|
* - rcl/graph.h
|
||||||
|
*
|
||||||
|
* Further still there are some useful abstractions and utilities:
|
||||||
|
*
|
||||||
|
* - Allocator concept, which can used to control allocation in `rcl_*` functions
|
||||||
|
* - rcl/allocator.h
|
||||||
|
* - Concept of ROS Time and access to steady and system wall time
|
||||||
|
* - rcl/time.h
|
||||||
|
* - Error handling functionality (C style)
|
||||||
|
* - rcl/error_handling.h
|
||||||
|
* - Macros
|
||||||
|
* - rcl/macros.h
|
||||||
|
* - Return code types
|
||||||
|
* - rcl/types.h
|
||||||
|
* - Macros for controlling symbol visibility on the library
|
||||||
|
* - rcl/visibility_control.h
|
||||||
|
*/
|
||||||
|
|
||||||
#ifndef RCL__RCL_H_
|
#ifndef RCL__RCL_H_
|
||||||
#define RCL__RCL_H_
|
#define RCL__RCL_H_
|
||||||
|
|
||||||
|
@ -29,37 +73,41 @@ extern "C"
|
||||||
#include "rcl/visibility_control.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.
|
||||||
*
|
*
|
||||||
* This function can only be run once after starting the program, and once
|
* This function can only be run once after starting the program, and once
|
||||||
* after each call to rcl_shutdown.
|
* after each call to rcl_shutdown().
|
||||||
* Repeated calls will fail with RCL_RET_ALREADY_INIT.
|
* Repeated calls will fail with `RCL_RET_ALREADY_INIT`.
|
||||||
* This function is not thread safe.
|
|
||||||
*
|
*
|
||||||
* This function can be called any time after rcl_shutdown is called, but it
|
* This function can be called any time after rcl_shutdown() is called, but it
|
||||||
* cannot be called from within a callback being executed by an rcl executor.
|
* cannot be called from within a callback being executed by an rcl executor.
|
||||||
* For example, you can call rcl_shutdown from within a timer callback, but
|
* For example, you can call rcl_shutdown() from within a timer callback, but
|
||||||
* you have to return from the callback, and therefore exit any in-progress
|
* you have to return from the callback, and therefore exit any in-progress
|
||||||
* call to a spin function, before calling rcl_init again.
|
* call to a spin function, before calling rcl_init() again.
|
||||||
*
|
*
|
||||||
* The argc and argv parameters can contain command line arguments for the
|
* The `argc` and `argv` parameters can contain command line arguments for the
|
||||||
* program.
|
* program.
|
||||||
* rcl specific arguments will be parsed and removed, but other arguments will
|
* rcl specific arguments will be parsed and removed, but other arguments will
|
||||||
* be ignored.
|
* be ignored.
|
||||||
* If argc is 0 and argv is NULL no parameters will be parsed.
|
* If `argc` is `0` and `argv` is `NULL` no parameters will be parsed.
|
||||||
*
|
*
|
||||||
* This function allocates heap memory.
|
* <hr>
|
||||||
* This function is not thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* ------------------ | -------------
|
||||||
* atomic_is_lock_free() returns true for atomic_uint_least64_t.
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \param[in] argc number of strings in argv
|
* \param[in] argc number of strings in argv
|
||||||
* \param[in] argv command line arguments; rcl specific arguments are removed
|
* \param[in] argv command line arguments; rcl specific arguments are removed
|
||||||
* \param[in] allocator allocator to be used during rcl_init and rcl_shutdown
|
* \param[in] allocator rcl_allocator_t used in rcl_init() and rcl_shutdown()
|
||||||
* \return RCL_RET_OK if initialization is successful, or
|
* \return `RCL_RET_OK` if initialization is successful, or
|
||||||
* RCL_RET_ALREADY_INIT if rcl_init has already been called, or
|
* \return `RCL_RET_ALREADY_INIT` if rcl_init has already been called, or
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -67,28 +115,34 @@ rcl_ret_t
|
||||||
rcl_init(int argc, char ** argv, rcl_allocator_t allocator);
|
rcl_init(int argc, char ** argv, rcl_allocator_t allocator);
|
||||||
|
|
||||||
/// Signal global shutdown of rcl.
|
/// Signal global shutdown of rcl.
|
||||||
/* This function does not have to be called on exit, but does have to be called
|
/**
|
||||||
* making a repeat call to rcl_init.
|
* This function does not have to be called on exit, but does have to be called
|
||||||
|
* making a repeat call to rcl_init().
|
||||||
*
|
*
|
||||||
* This function can only be called once after each call to rcl_init.
|
* This function can only be called once after each call to rcl_init().
|
||||||
* Repeated calls will fail with RCL_RET_NOT_INIT.
|
* Repeated calls will fail with RCL_RET_NOT_INIT.
|
||||||
* This function is not thread safe.
|
* This function is not thread safe.
|
||||||
*
|
*
|
||||||
* When this function is called:
|
* When this function is called:
|
||||||
* - Any rcl objects created since the last call to rcl_init are invalidated.
|
* - Any rcl objects created since the last call to rcl_init() are invalidated.
|
||||||
* - Calls to rcl_ok will return false.
|
* - Calls to rcl_ok() will return `false`.
|
||||||
* - Any executors waiting for work (within a call to spin) are interrupted.
|
* - Any executors waiting for work (within a call to spin) are interrupted.
|
||||||
* - No new work (executing callbacks) will be done in executors.
|
* - No new work (executing callbacks) will be done in executors.
|
||||||
* - Currently running work in executors will be finished.
|
* - Currently running work in executors will be finished.
|
||||||
*
|
*
|
||||||
* This function manipulates heap memory.
|
* <hr>
|
||||||
* This function is thread-safe, except with rcl_init().
|
* Attribute | Adherence
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* ------------------ | -------------
|
||||||
* atomic_is_lock_free() returns true for atomic_uint_least64_t.
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | Yes [1]
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [2]
|
||||||
|
* <i>[1] not thread-safe with rcl_init()</i>
|
||||||
|
* <i>[2] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \return RCL_RET_OK if the shutdown was completed successfully, or
|
* \return `RCL_RET_OK` if the shutdown was completed successfully, or
|
||||||
* RCL_RET_NOT_INIT if rcl is not currently initialized, or
|
* \return `RCL_RET_NOT_INIT` if rcl is not currently initialized, or
|
||||||
* RCL_RET_ERROR if an unspecified error occur.
|
* \return `RCL_RET_ERROR` if an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -96,25 +150,34 @@ rcl_ret_t
|
||||||
rcl_shutdown(void);
|
rcl_shutdown(void);
|
||||||
|
|
||||||
/// 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.
|
||||||
*
|
*
|
||||||
* This function does not allocate memory.
|
* <hr>
|
||||||
* This function is thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* ------------------ | -------------
|
||||||
* atomic_is_lock_free() returns true for atomic_uint_least64_t.
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \return a unique id specific to this rcl instance, or 0 if not initialized.
|
* \return a unique id specific to this rcl instance, or `0` if not initialized.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
uint64_t
|
uint64_t
|
||||||
rcl_get_instance_id(void);
|
rcl_get_instance_id(void);
|
||||||
|
|
||||||
/// Return true if rcl is currently initialized, otherwise false.
|
/// Return `true` if rcl is currently initialized, otherwise `false`.
|
||||||
/* This function does not allocate memory.
|
/**
|
||||||
* This function is thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* ------------------ | -------------
|
||||||
* atomic_is_lock_free() returns true for atomic_uint_least64_t.
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t`</i>
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
|
|
@ -29,7 +29,7 @@ extern "C"
|
||||||
/// Internal rcl implementation struct.
|
/// Internal rcl implementation struct.
|
||||||
struct rcl_service_impl_t;
|
struct rcl_service_impl_t;
|
||||||
|
|
||||||
/// Handle for a rcl service.
|
/// Structure which encapsulates a ROS Service.
|
||||||
typedef struct rcl_service_t
|
typedef struct rcl_service_t
|
||||||
{
|
{
|
||||||
struct rcl_service_impl_t * impl;
|
struct rcl_service_impl_t * impl;
|
||||||
|
@ -41,15 +41,14 @@ typedef struct rcl_service_options_t
|
||||||
/// Middleware quality of service settings for the service.
|
/// Middleware quality of service settings for the service.
|
||||||
rmw_qos_profile_t qos;
|
rmw_qos_profile_t qos;
|
||||||
/// Custom allocator for the service, used for incidental allocations.
|
/// Custom allocator for the service, used for incidental allocations.
|
||||||
/* For default behavior (malloc/free), see: rcl_get_default_allocator() */
|
/** For default behavior (malloc/free), see: rcl_get_default_allocator() */
|
||||||
rcl_allocator_t allocator;
|
rcl_allocator_t allocator;
|
||||||
} rcl_service_options_t;
|
} rcl_service_options_t;
|
||||||
|
|
||||||
/// Return a rcl_service_t struct with members set to NULL.
|
/// Return a rcl_service_t struct with members set to `NULL`.
|
||||||
/* Should be called to get a null rcl_service_t before passing to
|
/**
|
||||||
* rcl_initalize_service().
|
* Should be called to get a null rcl_service_t before passing to
|
||||||
* It's also possible to use calloc() instead of this if the rcl_service_t
|
* rcl_service_init().
|
||||||
* is being allocated on the heap.
|
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -57,7 +56,8 @@ rcl_service_t
|
||||||
rcl_get_zero_initialized_service(void);
|
rcl_get_zero_initialized_service(void);
|
||||||
|
|
||||||
/// Initialize a rcl service.
|
/// Initialize a rcl service.
|
||||||
/* After calling this function on a rcl_service_t, it can be used to take
|
/**
|
||||||
|
* After calling this function on a rcl_service_t, it can be used to take
|
||||||
* requests of the given type to the given topic using rcl_take_request().
|
* requests of the given type to the given topic using rcl_take_request().
|
||||||
* It can also send a response to a request using rcl_send_response().
|
* It can also send a response to a request using rcl_send_response().
|
||||||
*
|
*
|
||||||
|
@ -68,28 +68,31 @@ rcl_get_zero_initialized_service(void);
|
||||||
* When the user defines a ROS service, code is generated which provides the
|
* When the user defines a ROS service, code is generated which provides the
|
||||||
* required rosidl_service_type_support_t object.
|
* required rosidl_service_type_support_t object.
|
||||||
* This object can be obtained using a language appropriate mechanism.
|
* This object can be obtained using a language appropriate mechanism.
|
||||||
* \TODO(wjwwood) probably should talk about this once and link to it instead
|
* \todo TODO(wjwwood) write these instructions once and link to it instead
|
||||||
* \TODO(jacquelinekay) reworded this for services with substitutions, should it refer to messages?
|
* For C a macro can be used (for example `example_interfaces/AddTwoInts`):
|
||||||
* For C this macro can be used (using example_interfaces/AddTwoInts as an example):
|
|
||||||
*
|
*
|
||||||
* #include <rosidl_generator_c/service_type_support.h>
|
* ```c
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <rosidl_generator_c/service_type_support.h>
|
||||||
* rosidl_service_type_support_t * ts =
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
* ROSIDL_GET_SERVICE_TYPE_SUPPORT(example_interfaces, AddTwoInts);
|
* rosidl_service_type_support_t * ts =
|
||||||
|
* ROSIDL_GET_SERVICE_TYPE_SUPPORT(example_interfaces, AddTwoInts);
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* For C++ a template function is used:
|
* For C++ a template function is used:
|
||||||
*
|
*
|
||||||
* #include <rosidl_generator_cpp/service_type_support.hpp>
|
* ```cpp
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <rosidl_generator_cpp/service_type_support.hpp>
|
||||||
* rosidl_service_type_support_t * ts = rosidl_generator_cpp::get_service_type_support_handle<
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
* example_interfaces::srv::AddTwoInts>();
|
* rosidl_service_type_support_t * ts = rosidl_generator_cpp::get_service_type_support_handle<
|
||||||
|
* example_interfaces::srv::AddTwoInts>();
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* The rosidl_service_type_support_t object contains service type specific
|
* The rosidl_service_type_support_t object contains service type specific
|
||||||
* information used to send or take requests and responses.
|
* information used to send or take requests and responses.
|
||||||
*
|
*
|
||||||
* \TODO(wjwwood) update this once we've come up with an official scheme.
|
* \todo TODO(wjwwood) update this once we've come up with an official scheme.
|
||||||
* The service name must be a non-empty string which follows the service/topic naming
|
* The service name must be a non-empty string which follows the service/topic
|
||||||
* format.
|
* naming format.
|
||||||
*
|
*
|
||||||
* The options struct allows the user to set the quality of service settings as
|
* The options struct allows the user to set the quality of service settings as
|
||||||
* well as a custom allocator which is used when initializing/finalizing the
|
* well as a custom allocator which is used when initializing/finalizing the
|
||||||
|
@ -97,34 +100,44 @@ rcl_get_zero_initialized_service(void);
|
||||||
*
|
*
|
||||||
* Expected usage (for C services):
|
* Expected usage (for C services):
|
||||||
*
|
*
|
||||||
* #include <rcl/rcl.h>
|
* ```c
|
||||||
* #include <rosidl_generator_c/service_type_support.h>
|
* #include <rcl/rcl.h>
|
||||||
* #include <example_interfaces/srv/add_two_ints.h>
|
* #include <rosidl_generator_c/service_type_support.h>
|
||||||
|
* #include <example_interfaces/srv/add_two_ints.h>
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
||||||
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
|
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* rosidl_service_type_support_t * ts = ROSIDL_GET_SERVICE_TYPE_SUPPORT(
|
* rosidl_service_type_support_t * ts = ROSIDL_GET_SERVICE_TYPE_SUPPORT(
|
||||||
* example_interfaces, AddTwoInts);
|
* example_interfaces, AddTwoInts);
|
||||||
* rcl_service_t service = rcl_get_zero_initialized_service();
|
* rcl_service_t service = rcl_get_zero_initialized_service();
|
||||||
* rcl_service_options_t service_ops = rcl_service_get_default_options();
|
* rcl_service_options_t service_ops = rcl_service_get_default_options();
|
||||||
* ret = rcl_service_init(&service, &node, ts, "add_two_ints", &service_ops);
|
* ret = rcl_service_init(&service, &node, ts, "add_two_ints", &service_ops);
|
||||||
* // ... error handling, and on shutdown do finalization:
|
* // ... error handling, and on shutdown do finalization:
|
||||||
* ret = rcl_service_fini(&service, &node);
|
* ret = rcl_service_fini(&service, &node);
|
||||||
* // ... error handling for rcl_service_fini()
|
* // ... error handling for rcl_service_fini()
|
||||||
* ret = rcl_node_fini(&node);
|
* ret = rcl_node_fini(&node);
|
||||||
* // ... error handling for rcl_node_fini()
|
* // ... error handling for rcl_node_fini()
|
||||||
|
* ```
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[out] service preallocated service structure
|
* \param[out] service preallocated service structure
|
||||||
* \param[in] node valid rcl node handle
|
* \param[in] node valid rcl node handle
|
||||||
* \param[in] type_support type support object for the service's type
|
* \param[in] type_support type support object for the service's type
|
||||||
* \param[in] service_name the name of the service
|
* \param[in] service_name the name of the service
|
||||||
* \param[in] options service options, including quality of service settings
|
* \param[in] options service options, including quality of service settings
|
||||||
* \return RCL_RET_OK if service was initialized successfully, or
|
* \return `RCL_RET_OK` if service was initialized successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -137,21 +150,28 @@ rcl_service_init(
|
||||||
const rcl_service_options_t * options);
|
const rcl_service_options_t * options);
|
||||||
|
|
||||||
/// Finalize a rcl_service_t.
|
/// Finalize a rcl_service_t.
|
||||||
/* After calling, the node will no longer listen for requests for this service.
|
/**
|
||||||
|
* After calling, the node will no longer listen for requests for this service.
|
||||||
* (assuming this is the only service of this type in this node).
|
* (assuming this is the only service of this type in this node).
|
||||||
*
|
*
|
||||||
* After calling, calls to rcl_wait, rcl_take_request, and rcl_send_response will fail when using
|
* After calling, calls to rcl_wait(), rcl_take_request(), and
|
||||||
* this service.
|
* rcl_send_response() will fail when using this service.
|
||||||
* Additionally rcl_wait will be interrupted if currently blocking.
|
* Additionally rcl_wait() will be interrupted if currently blocking.
|
||||||
* However, the given node handle is still valid.
|
* However, the given node handle is still valid.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] service handle to the service to be deinitialized
|
* \param[inout] service handle to the service to be deinitialized
|
||||||
* \param[in] node handle to the node used to create the service
|
* \param[in] node handle to the node used to create the service
|
||||||
* \return RCL_RET_OK if service was deinitialized successfully, or
|
* \return `RCL_RET_OK` if service was deinitialized successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -159,13 +179,20 @@ rcl_ret_t
|
||||||
rcl_service_fini(rcl_service_t * service, rcl_node_t * node);
|
rcl_service_fini(rcl_service_t * service, rcl_node_t * node);
|
||||||
|
|
||||||
/// Return the default service options in a rcl_service_options_t.
|
/// Return the default service options in a rcl_service_options_t.
|
||||||
|
/**
|
||||||
|
* The defaults are:
|
||||||
|
*
|
||||||
|
* - qos = rmw_qos_profile_services_default
|
||||||
|
* - allocator = rcl_get_default_allocator()
|
||||||
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_service_options_t
|
rcl_service_options_t
|
||||||
rcl_service_get_default_options(void);
|
rcl_service_get_default_options(void);
|
||||||
|
|
||||||
/// Take a pending ROS request using a rcl service.
|
/// Take a pending ROS request using a rcl service.
|
||||||
/* It is the job of the caller to ensure that the type of the ros_request
|
/**
|
||||||
|
* It is the job of the caller to ensure that the type of the ros_request
|
||||||
* argument and the type associate with the service, via the type
|
* argument and the type associate with the service, via the type
|
||||||
* support, match.
|
* support, match.
|
||||||
* Passing a different type to rcl_take produces undefined behavior and cannot
|
* Passing a different type to rcl_take produces undefined behavior and cannot
|
||||||
|
@ -188,14 +215,23 @@ rcl_service_get_default_options(void);
|
||||||
* request_header is a pointer to pre-allocated a rmw struct containing
|
* request_header is a pointer to pre-allocated a rmw struct containing
|
||||||
* meta-information about the request (e.g. the sequence number).
|
* meta-information about the request (e.g. the sequence number).
|
||||||
*
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Maybe [1]
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <i>[1] only if required when filling the request, avoided for fixed sizes</i>
|
||||||
|
*
|
||||||
* \param[in] service the handle to the service from which to take
|
* \param[in] service the handle to the service from which to take
|
||||||
* \param[inout] request_header ptr to the struct holding metadata about the request ID
|
* \param[inout] request_header ptr to the struct holding metadata about the request ID
|
||||||
* \param[inout] ros_request type-erased ptr to an allocated ROS request message
|
* \param[inout] ros_request type-erased ptr to an allocated ROS request message
|
||||||
* \return RCL_RET_OK if the request was taken, or
|
* \return `RCL_RET_OK` if the request was taken, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_SERVICE_INVALID if the service is invalid, or
|
* \return `RCL_RET_SERVICE_INVALID` if the service is invalid, or
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -206,37 +242,49 @@ rcl_take_request(
|
||||||
void * ros_request);
|
void * ros_request);
|
||||||
|
|
||||||
/// Send a ROS response to a client using a service.
|
/// Send a ROS response to a client using a service.
|
||||||
/* It is the job of the caller to ensure that the type of the ros_response
|
/**
|
||||||
|
* It is the job of the caller to ensure that the type of the `ros_response`
|
||||||
* parameter and the type associate with the service (via the type support)
|
* parameter and the type associate with the service (via the type support)
|
||||||
* match.
|
* match.
|
||||||
* Passing a different type to send_response produces undefined behavior and cannot
|
* Passing a different type to send_response produces undefined behavior and
|
||||||
* be checked by this function and therefore no deliberate error will occur.
|
* cannot be checked by this function and therefore no deliberate error will
|
||||||
|
* occur.
|
||||||
*
|
*
|
||||||
* send_response is an non-blocking call.
|
* send_response() is an non-blocking call.
|
||||||
*
|
*
|
||||||
* The ROS response message given by the ros_response void pointer is always owned by the
|
* The ROS response message given by the `ros_response` void pointer is always
|
||||||
* calling code, but should remain constant during send_response.
|
* owned by the calling code, but should remain constant during
|
||||||
|
* rcl_send_response().
|
||||||
*
|
*
|
||||||
e This function is thread safe so long as access to both the service and the
|
e This function is thread safe so long as access to both the service and the
|
||||||
* ros_response is synchronized.
|
* `ros_response` is synchronized.
|
||||||
* That means that calling rcl_send_response from multiple threads is allowed, but
|
* That means that calling rcl_send_response() from multiple threads is
|
||||||
* calling rcl_send_response at the same time as non-thread safe service functions
|
* allowed, but calling rcl_send_response() at the same time as non-thread safe
|
||||||
* is not, e.g. calling rcl_send_response and rcl_service_fini concurrently
|
* service functions is not, e.g. calling rcl_send_response() and
|
||||||
* is not allowed.
|
* rcl_service_fini() concurrently is not allowed.
|
||||||
* Before calling rcl_send_response the message can change and after calling
|
* Before calling rcl_send_response() the message can change and after calling
|
||||||
* rcl_send_response the message can change, but it cannot be changed during the
|
* rcl_send_response() the message can change, but it cannot be changed during
|
||||||
* send_response call.
|
* the rcl_send_response() call.
|
||||||
* The same ros_response, however, can be passed to multiple calls of
|
* The same `ros_response`, however, can be passed to multiple calls of
|
||||||
* rcl_send_response simultaneously, even if the services differ.
|
* rcl_send_response() simultaneously, even if the services differ.
|
||||||
* The ros_response is unmodified by rcl_send_response.
|
* The `ros_response` is unmodified by rcl_send_response().
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes [1]
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <i>[1] for unique pairs of services and responses, see above for more</i>
|
||||||
*
|
*
|
||||||
* \param[in] service handle to the service which will make the response
|
* \param[in] service handle to the service which will make the response
|
||||||
* \param[inout] response_header ptr to the struct holding metadata about the request ID
|
* \param[inout] response_header ptr to the struct holding metadata about the request ID
|
||||||
* \param[in] ros_response type-erased pointer to the ROS response message
|
* \param[in] ros_response type-erased pointer to the ROS response message
|
||||||
* \return RCL_RET_OK if the response was sent successfully, or
|
* \return `RCL_RET_OK` if the response was sent successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_SERVICE_INVALID if the service is invalid, or
|
* \return `RCL_RET_SERVICE_INVALID` if the service is invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -247,19 +295,26 @@ rcl_send_response(
|
||||||
void * ros_response);
|
void * ros_response);
|
||||||
|
|
||||||
/// Get the topic name for the service.
|
/// Get the topic name for the service.
|
||||||
/* This function returns the service's internal topic name string.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if the:
|
* This function returns the service's internal topic name string.
|
||||||
* - service is NULL
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - service is `NULL`
|
||||||
* - service is invalid (never called init, called fini, or invalid)
|
* - service is invalid (never called init, called fini, or invalid)
|
||||||
*
|
*
|
||||||
* The returned string is only valid as long as the service is valid.
|
* The returned string is only valid as long as the service is valid.
|
||||||
* The value of the string may change if the topic name changes, and therefore
|
* The value of the string may change if the topic name changes, and therefore
|
||||||
* copying the string is recommended if this is a concern.
|
* copying the string is recommended if this is a concern.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe, and copying the result is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[in] service the pointer to the service
|
* \param[in] service the pointer to the service
|
||||||
* \return name string if successful, otherwise NULL
|
* \return name string if successful, otherwise `NULL`
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -267,19 +322,26 @@ const char *
|
||||||
rcl_service_get_service_name(const rcl_service_t * service);
|
rcl_service_get_service_name(const rcl_service_t * service);
|
||||||
|
|
||||||
/// Return the rcl service options.
|
/// Return the rcl service options.
|
||||||
/* This function returns the service's internal options struct.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if the:
|
* This function returns the service's internal options struct.
|
||||||
* - service is NULL
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - service is `NULL`
|
||||||
* - service is invalid (never called init, called fini, or invalid)
|
* - service is invalid (never called init, called fini, or invalid)
|
||||||
*
|
*
|
||||||
* The returned struct is only valid as long as the service is valid.
|
* The returned struct is only valid as long as the service is valid.
|
||||||
* The values in the struct may change if the service's options change,
|
* The values in the struct may change if the service's options change,
|
||||||
* and therefore copying the struct is recommended if this is a concern.
|
* and therefore copying the struct is recommended if this is a concern.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe, and copying the result is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[in] service pointer to the service
|
* \param[in] service pointer to the service
|
||||||
* \return options struct if successful, otherwise NULL
|
* \return options struct if successful, otherwise `NULL`
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -287,9 +349,10 @@ const rcl_service_options_t *
|
||||||
rcl_service_get_options(const rcl_service_t * service);
|
rcl_service_get_options(const rcl_service_t * service);
|
||||||
|
|
||||||
/// Return the rmw service handle.
|
/// Return the rmw service handle.
|
||||||
/* The handle returned is a pointer to the internally held rmw handle.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if the:
|
* The handle returned is a pointer to the internally held rmw handle.
|
||||||
* - service is NULL
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - service is `NULL`
|
||||||
* - service is invalid (never called init, called fini, or invalid)
|
* - service is invalid (never called init, called fini, or invalid)
|
||||||
*
|
*
|
||||||
* The returned handle is made invalid if the service is finalized or if
|
* The returned handle is made invalid if the service is finalized or if
|
||||||
|
@ -300,10 +363,16 @@ rcl_service_get_options(const rcl_service_t * service);
|
||||||
* this function each time it is needed and avoid use of the handle
|
* this function each time it is needed and avoid use of the handle
|
||||||
* concurrently with functions that might change it.
|
* concurrently with functions that might change it.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[in] service pointer to the rcl service
|
* \param[in] service pointer to the rcl service
|
||||||
* \return rmw service handle if successful, otherwise NULL
|
* \return rmw service handle if successful, otherwise `NULL`
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
|
|
@ -29,7 +29,7 @@ extern "C"
|
||||||
/// Internal rcl implementation struct.
|
/// Internal rcl implementation struct.
|
||||||
struct rcl_subscription_impl_t;
|
struct rcl_subscription_impl_t;
|
||||||
|
|
||||||
/// Handle for a rcl subscription.
|
/// Structure which encapsulates a ROS Subscription.
|
||||||
typedef struct rcl_subscription_t
|
typedef struct rcl_subscription_t
|
||||||
{
|
{
|
||||||
struct rcl_subscription_impl_t * impl;
|
struct rcl_subscription_impl_t * impl;
|
||||||
|
@ -43,15 +43,14 @@ typedef struct rcl_subscription_options_t
|
||||||
/// If true, messages published from within the same node are ignored.
|
/// If true, messages published from within the same node are ignored.
|
||||||
bool ignore_local_publications;
|
bool ignore_local_publications;
|
||||||
/// Custom allocator for the subscription, used for incidental allocations.
|
/// Custom allocator for the subscription, used for incidental allocations.
|
||||||
/* For default behavior (malloc/free), see: rcl_get_default_allocator() */
|
/** For default behavior (malloc/free), see: rcl_get_default_allocator() */
|
||||||
rcl_allocator_t allocator;
|
rcl_allocator_t allocator;
|
||||||
} rcl_subscription_options_t;
|
} rcl_subscription_options_t;
|
||||||
|
|
||||||
/// Return a rcl_subscription_t struct with members set to NULL.
|
/// Return a rcl_subscription_t struct with members set to `NULL`.
|
||||||
/* Should be called to get a null rcl_subscription_t before passing to
|
/**
|
||||||
* rcl_initalize_subscription().
|
* Should be called to get a null rcl_subscription_t before passing to
|
||||||
* It's also possible to use calloc() instead of this if the rcl_subscription_t
|
* rcl_subscription_init().
|
||||||
* is being allocated on the heap.
|
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -59,7 +58,8 @@ rcl_subscription_t
|
||||||
rcl_get_zero_initialized_subscription(void);
|
rcl_get_zero_initialized_subscription(void);
|
||||||
|
|
||||||
/// Initialize a ROS subscription.
|
/// Initialize a ROS subscription.
|
||||||
/* After calling this function on a rcl_subscription_t, it can be used to take
|
/**
|
||||||
|
* After calling this function on a rcl_subscription_t, it can be used to take
|
||||||
* messages of the given type to the given topic using rcl_take().
|
* messages of the given type to the given topic using rcl_take().
|
||||||
*
|
*
|
||||||
* The given rcl_node_t must be valid and the resulting rcl_subscription_t is
|
* The given rcl_node_t must be valid and the resulting rcl_subscription_t is
|
||||||
|
@ -69,25 +69,29 @@ rcl_get_zero_initialized_subscription(void);
|
||||||
* When the user defines a ROS message, code is generated which provides the
|
* When the user defines a ROS message, code is generated which provides the
|
||||||
* required rosidl_message_type_support_t object.
|
* required rosidl_message_type_support_t object.
|
||||||
* This object can be obtained using a language appropriate mechanism.
|
* This object can be obtained using a language appropriate mechanism.
|
||||||
* \TODO(wjwwood) probably should talk about this once and link to it instead
|
* \todo TODO(wjwwood) write these instructions once and link to it instead
|
||||||
* For C this macro can be used (using std_msgs/String as an example):
|
* For C a macro can be used (for example `std_msgs/String`):
|
||||||
*
|
*
|
||||||
* #include <rosidl_generator_c/message_type_support.h>
|
* ```c
|
||||||
* #include <std_msgs/msgs/string.h>
|
* #include <rosidl_generator_c/message_type_support.h>
|
||||||
* rosidl_message_type_support_t * string_ts =
|
* #include <std_msgs/msgs/string.h>
|
||||||
* ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
|
* rosidl_message_type_support_t * string_ts =
|
||||||
|
* ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* For C++ a template function is used:
|
* For C++ a template function is used:
|
||||||
*
|
*
|
||||||
* #include <rosidl_generator_cpp/message_type_support.hpp>
|
* ```cpp
|
||||||
* #include <std_msgs/msgs/string.hpp>
|
* #include <rosidl_generator_cpp/message_type_support.hpp>
|
||||||
* rosidl_message_type_support_t * string_ts =
|
* #include <std_msgs/msgs/string.hpp>
|
||||||
* rosidl_generator_cpp::get_message_type_support_handle<std_msgs::msg::String>();
|
* rosidl_message_type_support_t * string_ts =
|
||||||
|
* rosidl_generator_cpp::get_message_type_support_handle<std_msgs::msg::String>();
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* The rosidl_message_type_support_t object contains message type specific
|
* The rosidl_message_type_support_t object contains message type specific
|
||||||
* information used to publish messages.
|
* information used to publish messages.
|
||||||
*
|
*
|
||||||
* \TODO(wjwwood) update this once we've come up with an official scheme.
|
* \todo TODO(wjwwood) update this once we've come up with an official scheme.
|
||||||
* The topic name must be a non-empty string which follows the topic naming
|
* The topic name must be a non-empty string which follows the topic naming
|
||||||
* format.
|
* format.
|
||||||
*
|
*
|
||||||
|
@ -98,35 +102,43 @@ rcl_get_zero_initialized_subscription(void);
|
||||||
*
|
*
|
||||||
* Expected usage (for C messages):
|
* Expected usage (for C messages):
|
||||||
*
|
*
|
||||||
* #include <rcl/rcl.h>
|
* ```c
|
||||||
* #include <rosidl_generator_c/message_type_support.h>
|
* #include <rcl/rcl.h>
|
||||||
* #include <std_msgs/msgs/string.h>
|
* #include <rosidl_generator_c/message_type_support.h>
|
||||||
|
* #include <std_msgs/msgs/string.h>
|
||||||
*
|
*
|
||||||
* rcl_node_t node = rcl_get_zero_initialized_node();
|
* rcl_node_t node = rcl_get_zero_initialized_node();
|
||||||
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
* rcl_node_options_t node_ops = rcl_node_get_default_options();
|
||||||
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
|
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* rosidl_message_type_support_t * ts = ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
|
* rosidl_message_type_support_t * ts = ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
|
||||||
* rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
|
* rcl_subscription_t subscription = rcl_get_zero_initialized_subscription();
|
||||||
* rcl_subscription_options_t subscription_ops = rcl_subscription_get_default_options();
|
* rcl_subscription_options_t subscription_ops = rcl_subscription_get_default_options();
|
||||||
* ret = rcl_subscription_init(&subscription, &node, ts, "chatter", &subscription_ops);
|
* ret = rcl_subscription_init(&subscription, &node, ts, "chatter", &subscription_ops);
|
||||||
* // ... error handling, and when finished deinitialization
|
* // ... error handling, and when finished deinitialization
|
||||||
* ret = rcl_subscription_fini(&subscription, &node);
|
* ret = rcl_subscription_fini(&subscription, &node);
|
||||||
* // ... error handling for rcl_subscription_fini()
|
* // ... error handling for rcl_subscription_fini()
|
||||||
* ret = rcl_node_fini(&node);
|
* ret = rcl_node_fini(&node);
|
||||||
* // ... error handling for rcl_node_fini()
|
* // ... error handling for rcl_node_fini()
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[out] subscription preallocated subscription structure
|
* \param[out] subscription preallocated subscription structure
|
||||||
* \param[in] node valid rcl node handle
|
* \param[in] node valid rcl node handle
|
||||||
* \param[in] type_support type support object for the topic's type
|
* \param[in] type_support type support object for the topic's type
|
||||||
* \param[in] topic_name the name of the topic
|
* \param[in] topic_name the name of the topic
|
||||||
* \param[in] options subscription options, including quality of service settings
|
* \param[in] options subscription options, including quality of service settings
|
||||||
* \return RCL_RET_OK if subscription was initialized successfully, or
|
* \return `RCL_RET_OK` if subscription was initialized successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -139,7 +151,8 @@ rcl_subscription_init(
|
||||||
const rcl_subscription_options_t * options);
|
const rcl_subscription_options_t * options);
|
||||||
|
|
||||||
/// Finalize a rcl_subscription_t.
|
/// Finalize a rcl_subscription_t.
|
||||||
/* After calling, the node will no longer be subscribed on this topic
|
/**
|
||||||
|
* After calling, the node will no longer be subscribed on this topic
|
||||||
* (assuming this is the only subscription on this topic in this node).
|
* (assuming this is the only subscription on this topic in this node).
|
||||||
*
|
*
|
||||||
* After calling, calls to rcl_wait and rcl_take will fail when using this
|
* After calling, calls to rcl_wait and rcl_take will fail when using this
|
||||||
|
@ -147,13 +160,19 @@ rcl_subscription_init(
|
||||||
* Additioanlly rcl_wait will be interrupted if currently blocking.
|
* Additioanlly rcl_wait will be interrupted if currently blocking.
|
||||||
* However, the given node handle is still valid.
|
* However, the given node handle is still valid.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] subscription handle to the subscription to be deinitialized
|
* \param[inout] subscription handle to the subscription to be deinitialized
|
||||||
* \param[in] node handle to the node used to create the subscription
|
* \param[in] node handle to the node used to create the subscription
|
||||||
* \return RCL_RET_OK if subscription was deinitialized successfully, or
|
* \return `RCL_RET_OK` if subscription was deinitialized successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -161,13 +180,21 @@ 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.
|
||||||
|
/**
|
||||||
|
* The defaults are:
|
||||||
|
*
|
||||||
|
* - ignore_local_publications = false
|
||||||
|
* - qos = rmw_qos_profile_default
|
||||||
|
* - allocator = rcl_get_default_allocator()
|
||||||
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_subscription_options_t
|
rcl_subscription_options_t
|
||||||
rcl_subscription_get_default_options(void);
|
rcl_subscription_get_default_options(void);
|
||||||
|
|
||||||
/// Take a ROS message from a topic using a rcl subscription.
|
/// Take a ROS message from a topic using a rcl subscription.
|
||||||
/* It is the job of the caller to ensure that the type of the ros_message
|
/**
|
||||||
|
* It is the job of the caller to ensure that the type of the ros_message
|
||||||
* argument and the type associate with the subscription, via the type
|
* argument and the type associate with the subscription, via the type
|
||||||
* support, match.
|
* support, match.
|
||||||
* Passing a different type to rcl_take produces undefined behavior and cannot
|
* Passing a different type to rcl_take produces undefined behavior and cannot
|
||||||
|
@ -193,18 +220,27 @@ rcl_subscription_get_default_options(void);
|
||||||
* process.
|
* process.
|
||||||
* The message_info argument should be an already allocated rmw_message_info_t
|
* The message_info argument should be an already allocated rmw_message_info_t
|
||||||
* structure.
|
* structure.
|
||||||
* Passing NULL for message_info will result in the argument being ignored.
|
* Passing `NULL` for message_info will result in the argument being ignored.
|
||||||
|
*
|
||||||
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Maybe [1]
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
|
* <i>[1] only if required when filling the message, avoided for fixed sizes</i>
|
||||||
*
|
*
|
||||||
* \param[in] subscription the handle to the subscription from which to take
|
* \param[in] subscription the handle to the subscription from which to take
|
||||||
* \param[inout] ros_message type-erased ptr to a allocated ROS message
|
* \param[inout] ros_message type-erased ptr to a allocated ROS message
|
||||||
* \param[out] message_info rmw struct which contains meta-data for the message
|
* \param[out] message_info rmw struct which contains meta-data for the message
|
||||||
* \return RCL_RET_OK if the message was published, or
|
* \return `RCL_RET_OK` if the message was published, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_SUBSCRIPTION_INVALID if the subscription is invalid, or
|
* \return `RCL_RET_SUBSCRIPTION_INVALID` if the subscription is invalid, or
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
* RCL_RET_SUBSCRIPTION_TAKE_FAILED if take failed but no error
|
* \return `RCL_RET_SUBSCRIPTION_TAKE_FAILED` if take failed but no error
|
||||||
* occurred in the middleware, or
|
* occurred in the middleware, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -215,19 +251,26 @@ rcl_take(
|
||||||
rmw_message_info_t * message_info);
|
rmw_message_info_t * message_info);
|
||||||
|
|
||||||
/// Get the topic name for the subscription.
|
/// Get the topic name for the subscription.
|
||||||
/* This function returns the subscription's internal topic name string.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if the:
|
* This function returns the subscription's internal topic name string.
|
||||||
* - subscription is NULL
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - subscription is `NULL`
|
||||||
* - subscription is invalid (never called init, called fini, or invalid)
|
* - subscription is invalid (never called init, called fini, or invalid)
|
||||||
*
|
*
|
||||||
* The returned string is only valid as long as the subscription is valid.
|
* The returned string is only valid as long as the subscription is valid.
|
||||||
* The value of the string may change if the topic name changes, and therefore
|
* The value of the string may change if the topic name changes, and therefore
|
||||||
* copying the string is recommended if this is a concern.
|
* copying the string is recommended if this is a concern.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe, and copying the result is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \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
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -235,19 +278,26 @@ const char *
|
||||||
rcl_subscription_get_topic_name(const rcl_subscription_t * subscription);
|
rcl_subscription_get_topic_name(const rcl_subscription_t * subscription);
|
||||||
|
|
||||||
/// Return the rcl subscription options.
|
/// Return the rcl subscription options.
|
||||||
/* This function returns the subscription's internal options struct.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if the:
|
* This function returns the subscription's internal options struct.
|
||||||
* - subscription is NULL
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - subscription is `NULL`
|
||||||
* - subscription is invalid (never called init, called fini, or invalid)
|
* - subscription is invalid (never called init, called fini, or invalid)
|
||||||
*
|
*
|
||||||
* The returned struct is only valid as long as the subscription is valid.
|
* The returned struct is only valid as long as the subscription is valid.
|
||||||
* The values in the struct may change if the subscription's options change,
|
* The values in the struct may change if the subscription's options change,
|
||||||
* and therefore copying the struct is recommended if this is a concern.
|
* and therefore copying the struct is recommended if this is a concern.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe, and copying the result is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \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
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -255,9 +305,10 @@ const rcl_subscription_options_t *
|
||||||
rcl_subscription_get_options(const rcl_subscription_t * subscription);
|
rcl_subscription_get_options(const rcl_subscription_t * subscription);
|
||||||
|
|
||||||
/// Return the rmw subscription handle.
|
/// Return the rmw subscription handle.
|
||||||
/* The handle returned is a pointer to the internally held rmw handle.
|
/**
|
||||||
* This function can fail, and therefore return NULL, if the:
|
* The handle returned is a pointer to the internally held rmw handle.
|
||||||
* - subscription is NULL
|
* This function can fail, and therefore return `NULL`, if the:
|
||||||
|
* - subscription is `NULL`
|
||||||
* - subscription is invalid (never called init, called fini, or invalid)
|
* - subscription is invalid (never called init, called fini, or invalid)
|
||||||
*
|
*
|
||||||
* The returned handle is made invalid if the subscription is finalized or if
|
* The returned handle is made invalid if the subscription is finalized or if
|
||||||
|
@ -268,10 +319,16 @@ rcl_subscription_get_options(const rcl_subscription_t * subscription);
|
||||||
* this function each time it is needed and avoid use of the handle
|
* this function each time it is needed and avoid use of the handle
|
||||||
* concurrently with functions that might change it.
|
* concurrently with functions that might change it.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \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
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
|
|
@ -24,14 +24,26 @@ extern "C"
|
||||||
#include "rcl/types.h"
|
#include "rcl/types.h"
|
||||||
#include "rcl/visibility_control.h"
|
#include "rcl/visibility_control.h"
|
||||||
|
|
||||||
|
/// Convenience macro to convert seconds to nanoseconds.
|
||||||
#define RCL_S_TO_NS(seconds) (seconds * (1000 * 1000 * 1000))
|
#define RCL_S_TO_NS(seconds) (seconds * (1000 * 1000 * 1000))
|
||||||
|
/// Convenience macro to convert milliseconds to nanoseconds.
|
||||||
#define RCL_MS_TO_NS(milliseconds) (milliseconds * (1000 * 1000))
|
#define RCL_MS_TO_NS(milliseconds) (milliseconds * (1000 * 1000))
|
||||||
|
/// Convenience macro to convert microseconds to nanoseconds.
|
||||||
#define RCL_US_TO_NS(microseconds) (microseconds * 1000)
|
#define RCL_US_TO_NS(microseconds) (microseconds * 1000)
|
||||||
|
|
||||||
|
/// Convenience macro to convert nanoseconds to seconds.
|
||||||
#define RCL_NS_TO_S(nanoseconds) (nanoseconds / (1000 * 1000 * 1000))
|
#define RCL_NS_TO_S(nanoseconds) (nanoseconds / (1000 * 1000 * 1000))
|
||||||
|
/// Convenience macro to convert nanoseconds to milliseconds.
|
||||||
#define RCL_NS_TO_MS(nanoseconds) (nanoseconds / (1000 * 1000))
|
#define RCL_NS_TO_MS(nanoseconds) (nanoseconds / (1000 * 1000))
|
||||||
|
/// Convenience macro to convert nanoseconds to microseconds.
|
||||||
#define RCL_NS_TO_US(nanoseconds) (nanoseconds / 1000)
|
#define RCL_NS_TO_US(nanoseconds) (nanoseconds / 1000)
|
||||||
|
|
||||||
|
/// A single point in time, measured in nanoseconds since the Unix epoch.
|
||||||
|
typedef uint64_t rcl_time_point_value_t;
|
||||||
|
/// A duration of time, measured in nanoseconds.
|
||||||
|
typedef int64_t rcl_duration_value_t;
|
||||||
|
|
||||||
|
/// Time source type, used to indicate the source of a time measurement.
|
||||||
enum rcl_time_source_type_t
|
enum rcl_time_source_type_t
|
||||||
{
|
{
|
||||||
RCL_TIME_SOURCE_UNINITIALIZED = 0,
|
RCL_TIME_SOURCE_UNINITIALIZED = 0,
|
||||||
|
@ -40,9 +52,7 @@ enum rcl_time_source_type_t
|
||||||
RCL_STEADY_TIME
|
RCL_STEADY_TIME
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef uint64_t rcl_time_point_value_t;
|
/// Encapsulation of a time source.
|
||||||
typedef int64_t rcl_duration_value_t;
|
|
||||||
|
|
||||||
typedef struct rcl_time_source_t
|
typedef struct rcl_time_source_t
|
||||||
{
|
{
|
||||||
enum rcl_time_source_type_t type;
|
enum rcl_time_source_type_t type;
|
||||||
|
@ -54,12 +64,15 @@ typedef struct rcl_time_source_t
|
||||||
} rcl_time_source_t;
|
} rcl_time_source_t;
|
||||||
|
|
||||||
struct rcl_ros_time_source_storage_t;
|
struct rcl_ros_time_source_storage_t;
|
||||||
|
|
||||||
|
/// A single point in time, measured in nanoseconds, the reference point is based on the source.
|
||||||
typedef struct rcl_time_point_t
|
typedef struct rcl_time_point_t
|
||||||
{
|
{
|
||||||
rcl_time_point_value_t nanoseconds;
|
rcl_time_point_value_t nanoseconds;
|
||||||
rcl_time_source_t * time_source;
|
rcl_time_source_t * time_source;
|
||||||
} rcl_time_point_t;
|
} rcl_time_point_t;
|
||||||
|
|
||||||
|
/// A duration of time, measured in nanoseconds and its source.
|
||||||
typedef struct rcl_duration_t
|
typedef struct rcl_duration_t
|
||||||
{
|
{
|
||||||
rcl_duration_value_t nanoseconds;
|
rcl_duration_value_t nanoseconds;
|
||||||
|
@ -75,7 +88,8 @@ typedef struct rcl_duration_t
|
||||||
// TODO(tfoote) integrate rate and timer implementations
|
// TODO(tfoote) integrate rate and timer implementations
|
||||||
|
|
||||||
/// Check if the time_source has valid values.
|
/// Check if the time_source has valid values.
|
||||||
/* This function returns true if the time source appears to be valid.
|
/**
|
||||||
|
* This function returns true if the time source appears to be valid.
|
||||||
* It will check that the type is not uninitialized, and that pointers
|
* It will check that the type is not uninitialized, and that pointers
|
||||||
* are not invalid.
|
* are not invalid.
|
||||||
* Note that if data is uninitialized it may give a false positive.
|
* Note that if data is uninitialized it may give a false positive.
|
||||||
|
@ -88,93 +102,99 @@ RCL_WARN_UNUSED
|
||||||
bool
|
bool
|
||||||
rcl_time_source_valid(rcl_time_source_t * time_source);
|
rcl_time_source_valid(rcl_time_source_t * time_source);
|
||||||
|
|
||||||
/// Initialize a timesource as a RCL_ROS_TIME time source.
|
/// Initialize a time_source as a RCL_ROS_TIME time source.
|
||||||
/* This will allocate all necessary internal structures, and initialize variables.
|
/**
|
||||||
|
* This will allocate all necessary internal structures, and initialize variables.
|
||||||
* It is specifically setting up a RCL_ROS_TIME time source.
|
* It is specifically setting up a RCL_ROS_TIME time source.
|
||||||
*
|
*
|
||||||
* \param[in] time_source the handle to the time_source which is being initialized
|
* \param[in] time_source the handle to the time_source which is being initialized
|
||||||
* \return RCL_RET_OK if the time source was successfully initialized, or
|
* \return `RCL_RET_OK` if the time source was successfully initialized, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_init_ros_time_source(rcl_time_source_t * time_source);
|
rcl_init_ros_time_source(rcl_time_source_t * time_source);
|
||||||
|
|
||||||
/// Finalize a timesource as a RCL_ROS_TIME time source.
|
/// Finalize a time_source as a `RCL_ROS_TIME` time source.
|
||||||
/* This will deallocate all necessary internal structures, and clean up any variables.
|
/**
|
||||||
* It is specifically setting up a RCL_ROS_TIME time source. It is expected to be paired with
|
* This will deallocate all necessary internal structures, and clean up any variables.
|
||||||
* the init fuction.
|
* It is specifically setting up a `RCL_ROS_TIME` time source. It is expected
|
||||||
|
* to be paired with the init fuction.
|
||||||
*
|
*
|
||||||
* \param[in] time_source the handle to the time_source which is being initialized
|
* \param[in] time_source the handle to the time_source which is being initialized
|
||||||
* \return RCL_RET_OK if the time source was successfully finalized, or
|
* \return `RCL_RET_OK` if the time source was successfully finalized, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_fini_ros_time_source(rcl_time_source_t * time_source);
|
rcl_fini_ros_time_source(rcl_time_source_t * time_source);
|
||||||
|
|
||||||
/// Initialize a timesource as a RCL_STEADY_TIME time source.
|
/// Initialize a time_source as a `RCL_STEADY_TIME` time source.
|
||||||
/* This will allocate all necessary internal structures, and initialize variables.
|
/**
|
||||||
* It is specifically setting up a RCL_STEADY_TIME time source.
|
* This will allocate all necessary internal structures, and initialize variables.
|
||||||
|
* It is specifically setting up a `RCL_STEADY_TIME` time source.
|
||||||
*
|
*
|
||||||
* \param[in] time_source the handle to the time_source which is being initialized
|
* \param[in] time_source the handle to the time_source which is being initialized
|
||||||
* \return RCL_RET_OK if the time source was successfully initialized, or
|
* \return `RCL_RET_OK` if the time source was successfully initialized, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_init_steady_time_source(rcl_time_source_t * time_source);
|
rcl_init_steady_time_source(rcl_time_source_t * time_source);
|
||||||
|
|
||||||
/// Finalize a timesource as a RCL_STEADY_TIME time source.
|
/// Finalize a time_source as a `RCL_STEADY_TIME` time source.
|
||||||
/* Finalize the timesource as a RCL_STEADY_TIME time source.
|
/**
|
||||||
|
* Finalize the time_source as a `RCL_STEADY_TIME` time source.
|
||||||
*
|
*
|
||||||
* This will deallocate all necessary internal structures, and clean up any variables.
|
* This will deallocate all necessary internal structures, and clean up any variables.
|
||||||
* It is specifically setting up a steady time source. It is expected to be paired with
|
* It is specifically setting up a steady time source. It is expected to be
|
||||||
* the init fuction.
|
* paired with the init fuction.
|
||||||
*
|
*
|
||||||
* \param[in] time_source the handle to the time_source which is being initialized
|
* \param[in] time_source the handle to the time_source which is being initialized
|
||||||
* \return RCL_RET_OK if the time source was successfully finalized, or
|
* \return `RCL_RET_OK` if the time source was successfully finalized, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_fini_steady_time_source(rcl_time_source_t * time_source);
|
rcl_fini_steady_time_source(rcl_time_source_t * time_source);
|
||||||
|
|
||||||
/// Initialize a timesource as a RCL_SYSTEM_TIME time source.
|
/// Initialize a time_source as a `RCL_SYSTEM_TIME` time source.
|
||||||
/* Initialize the timesource as a RCL_SYSTEM_TIME time source.
|
/**
|
||||||
|
* Initialize the time_source as a `RCL_SYSTEM_TIME` time source.
|
||||||
*
|
*
|
||||||
* This will allocate all necessary internal structures, and initialize variables.
|
* This will allocate all necessary internal structures, and initialize variables.
|
||||||
* It is specifically setting up a system time source.
|
* It is specifically setting up a system time source.
|
||||||
*
|
*
|
||||||
* \param[in] time_source the handle to the time_source which is being initialized
|
* \param[in] time_source the handle to the time_source which is being initialized
|
||||||
* \return RCL_RET_OK if the time source was successfully initialized, or
|
* \return `RCL_RET_OK` if the time source was successfully initialized, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_init_system_time_source(rcl_time_source_t * time_source);
|
rcl_init_system_time_source(rcl_time_source_t * time_source);
|
||||||
|
|
||||||
/// Finalize a timesource as a RCL_SYSTEM_TIME time source.
|
/// Finalize a time_source as a `RCL_SYSTEM_TIME` time source.
|
||||||
/* Finalize the timesource as a RCL_SYSTEM_TIME time source.
|
/**
|
||||||
|
* Finalize the time_source as a `RCL_SYSTEM_TIME` time source.
|
||||||
*
|
*
|
||||||
* This will deallocate all necessary internal structures, and clean up any variables.
|
* This will deallocate all necessary internal structures, and clean up any variables.
|
||||||
* It is specifically setting up a system time source. It is expected to be paired with
|
* It is specifically setting up a system time source. It is expected to be paired with
|
||||||
* the init fuction.
|
* the init fuction.
|
||||||
*
|
*
|
||||||
* \param[in] time_source the handle to the time_source which is being initialized.
|
* \param[in] time_source the handle to the time_source which is being initialized.
|
||||||
* \return RCL_RET_OK if the time source was successfully finalized, or
|
* \return `RCL_RET_OK` if the time source was successfully finalized, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -182,18 +202,20 @@ rcl_ret_t
|
||||||
rcl_fini_system_time_source(rcl_time_source_t * time_source);
|
rcl_fini_system_time_source(rcl_time_source_t * time_source);
|
||||||
|
|
||||||
/// Initialize a time point using the time_source.
|
/// Initialize a time point using the time_source.
|
||||||
/* This function will initialize the time_point using the time_source
|
/**
|
||||||
|
* This function will initialize the time_point using the time_source
|
||||||
* as a reference.
|
* as a reference.
|
||||||
* If the time_source is null it will use the system default time_source.
|
* If the time_source is null it will use the system default time_source.
|
||||||
*
|
*
|
||||||
* This will allocate all necessary internal structures, and initialize variables.
|
* This will allocate all necessary internal structures, and initialize variables.
|
||||||
* The time_source may be of types RCL_ROS_TIME, RCL_STEADY_TIME, or RCL_SYSTEM_TIME.
|
* The time_source may be of types `RCL_ROS_TIME`, `RCL_STEADY_TIME`, or
|
||||||
|
* `RCL_SYSTEM_TIME`.
|
||||||
*
|
*
|
||||||
* \param[in] time_point the handle to the time_source which is being initialized.
|
* \param[in] time_point the handle to the time_source which is being initialized.
|
||||||
* \param[in] time_source the handle to the time_source will be used for reference.
|
* \param[in] time_source the handle to the time_source will be used for reference.
|
||||||
* \return RCL_RET_OK if the last call time was retrieved successfully, or
|
* \return `RCL_RET_OK` if the last call time was retrieved successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -201,14 +223,15 @@ rcl_ret_t
|
||||||
rcl_init_time_point(rcl_time_point_t * time_point, rcl_time_source_t * time_source);
|
rcl_init_time_point(rcl_time_point_t * time_point, rcl_time_source_t * time_source);
|
||||||
|
|
||||||
/// Finalize a time_point
|
/// Finalize a time_point
|
||||||
/* Finalize the time_point such that it is ready for deallocation.
|
/**
|
||||||
|
* Finalize the time_point such that it is ready for deallocation.
|
||||||
*
|
*
|
||||||
* This will deallocate all necessary internal structures, and clean up any variables.
|
* This will deallocate all necessary internal structures, and clean up any variables.
|
||||||
*
|
*
|
||||||
* \param[in] time_point the handle to the time_source which is being finalized.
|
* \param[in] time_point the handle to the time_source which is being finalized.
|
||||||
* \return RCL_RET_OK if the last call time was retrieved successfully, or
|
* \return `RCL_RET_OK` if the last call time was retrieved successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -216,7 +239,8 @@ rcl_ret_t
|
||||||
rcl_fini_time_point(rcl_time_point_t * time_point);
|
rcl_fini_time_point(rcl_time_point_t * time_point);
|
||||||
|
|
||||||
/// Initialize a duration using the time_source.
|
/// Initialize a duration using the time_source.
|
||||||
/* This function will initialize the duration using the time_source as a reference.
|
/**
|
||||||
|
* This function will initialize the duration using the time_source as a reference.
|
||||||
* If the time_source is null it will use the system default time_source.
|
* If the time_source is null it will use the system default time_source.
|
||||||
*
|
*
|
||||||
* This will allocate all necessary internal structures, and initialize variables.
|
* This will allocate all necessary internal structures, and initialize variables.
|
||||||
|
@ -224,9 +248,9 @@ rcl_fini_time_point(rcl_time_point_t * time_point);
|
||||||
*
|
*
|
||||||
* \param[in] duration the handle to the duration which is being initialized.
|
* \param[in] duration the handle to the duration which is being initialized.
|
||||||
* \param[in] time_source the handle to the time_source will be used for reference.
|
* \param[in] time_source the handle to the time_source will be used for reference.
|
||||||
* \return RCL_RET_OK if the last call time was retrieved successfully, or
|
* \return `RCL_RET_OK` if the last call time was retrieved successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -234,22 +258,24 @@ rcl_ret_t
|
||||||
rcl_init_duration(rcl_duration_t * duration, rcl_time_source_t * time_source);
|
rcl_init_duration(rcl_duration_t * duration, rcl_time_source_t * time_source);
|
||||||
|
|
||||||
/// Finalize a duration
|
/// Finalize a duration
|
||||||
/* Finalize the duration such that it is ready for deallocation.
|
/**
|
||||||
|
* Finalize the duration such that it is ready for deallocation.
|
||||||
*
|
*
|
||||||
* This will deallocate all necessary internal structures, and clean up any variables.
|
* This will deallocate all necessary internal structures, and clean up any variables.
|
||||||
*
|
*
|
||||||
* \param[in] duration the handle to the duration which is being finalized.
|
* \param[in] duration the handle to the duration which is being finalized.
|
||||||
* \return RCL_RET_OK if the last call time was retrieved successfully, or
|
* \return `RCL_RET_OK` if the last call time was retrieved successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_fini_duration(rcl_duration_t * duration);
|
rcl_fini_duration(rcl_duration_t * duration);
|
||||||
|
|
||||||
/// Get the default RCL_ROS_TIME time source
|
/// Get the default `RCL_ROS_TIME` time source
|
||||||
/* This function will get the process default time source.
|
/**
|
||||||
|
* This function will get the process default time source.
|
||||||
* This time source is specifically of the ROS time abstraction,
|
* This time source is specifically of the ROS time abstraction,
|
||||||
* and may be overridden by updates.
|
* and may be overridden by updates.
|
||||||
*
|
*
|
||||||
|
@ -264,8 +290,9 @@ RCL_WARN_UNUSED
|
||||||
rcl_time_source_t *
|
rcl_time_source_t *
|
||||||
rcl_get_default_ros_time_source(void);
|
rcl_get_default_ros_time_source(void);
|
||||||
|
|
||||||
/// Get the default RCL_STEADY_TIME time source
|
/// Get the default `RCL_STEADY_TIME` time source
|
||||||
/* This function will get the process default time source.
|
/**
|
||||||
|
* This function will get the process default time source.
|
||||||
* This time source is specifically of the steady time abstraction,
|
* This time source is specifically of the steady time abstraction,
|
||||||
* it should not be able to be overridden..
|
* it should not be able to be overridden..
|
||||||
*
|
*
|
||||||
|
@ -280,8 +307,9 @@ RCL_WARN_UNUSED
|
||||||
rcl_time_source_t *
|
rcl_time_source_t *
|
||||||
rcl_get_default_steady_time_source(void);
|
rcl_get_default_steady_time_source(void);
|
||||||
|
|
||||||
/// Get the default RCL_SYSTEM_TIME time source
|
/// Get the default `RCL_SYSTEM_TIME` time source
|
||||||
/* This function will get the process default time source.
|
/**
|
||||||
|
* This function will get the process default time source.
|
||||||
* This time source is specifically of the system time abstraction,
|
* This time source is specifically of the system time abstraction,
|
||||||
* and may be overridden by updates to the system clock.
|
* and may be overridden by updates to the system clock.
|
||||||
*
|
*
|
||||||
|
@ -296,19 +324,20 @@ RCL_WARN_UNUSED
|
||||||
rcl_time_source_t *
|
rcl_time_source_t *
|
||||||
rcl_get_default_system_time_source(void);
|
rcl_get_default_system_time_source(void);
|
||||||
|
|
||||||
/// Set the current time on the RCL_ROS_TIME time source
|
/// Set the current time on the `RCL_ROS_TIME` time source
|
||||||
/* This function is used to set the time on a ros time source.
|
/**
|
||||||
* It will error if passed a differnt time source.
|
* This function is used to set the time on a ROS time source.
|
||||||
|
* It will error if passed a different time source.
|
||||||
*
|
*
|
||||||
* This should not block, except on Windows. One caveat is that
|
* This should not block, except on Windows. One caveat is that
|
||||||
* if the ros time abstraction is active, it will invoke the user
|
* if the ROS time abstraction is active, it will invoke the user
|
||||||
* defined callbacks, for pre and post update notifications. The
|
* defined callbacks, for pre and post update notifications. The
|
||||||
* calbacks are supposed to be short running and non-blocking.
|
* callbacks are supposed to be short running and non-blocking.
|
||||||
*
|
*
|
||||||
* \param[in] process_time_source The time source on which to set the value.
|
* \param[in] process_time_source The time source on which to set the value.
|
||||||
* \return RCL_RET_OK if the value was set successfully, or
|
* \return `RCL_RET_OK` if the value was set successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -316,7 +345,8 @@ rcl_ret_t
|
||||||
rcl_set_default_ros_time_source(rcl_time_source_t * process_time_source);
|
rcl_set_default_ros_time_source(rcl_time_source_t * process_time_source);
|
||||||
|
|
||||||
/// Compute the difference between two time points
|
/// Compute the difference between two time points
|
||||||
/* This function takes two time points and computes the duration between them.
|
/**
|
||||||
|
* This function takes two time points and computes the duration between them.
|
||||||
* The two time points must be using the same time abstraction, and the
|
* The two time points must be using the same time abstraction, and the
|
||||||
* resultant duration will also be of the same abstraction.
|
* resultant duration will also be of the same abstraction.
|
||||||
*
|
*
|
||||||
|
@ -326,9 +356,9 @@ rcl_set_default_ros_time_source(rcl_time_source_t * process_time_source);
|
||||||
* \param[in] start The time point for the start of the duration.
|
* \param[in] start The time point for the start of the duration.
|
||||||
* \param[in] finish The time point for the end of the duration.
|
* \param[in] finish The time point for the end of the duration.
|
||||||
* \param[out] delta The duration between the start and finish.
|
* \param[out] delta The duration between the start and finish.
|
||||||
* \return RCL_RET_OK if the difference was computed successfully, or
|
* \return `RCL_RET_OK` if the difference was computed successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -337,13 +367,14 @@ rcl_difference_times(rcl_time_point_t * start, rcl_time_point_t * finish,
|
||||||
rcl_duration_t * delta);
|
rcl_duration_t * delta);
|
||||||
|
|
||||||
/// Fill the time point with the current value of the associated clock.
|
/// Fill the time point with the current value of the associated clock.
|
||||||
/* This function will populate the data of the time_point object with the
|
/**
|
||||||
|
* This function will populate the data of the time_point object with the
|
||||||
* current value from it's associated time abstraction.
|
* current value from it's associated time abstraction.
|
||||||
*
|
*
|
||||||
* \param[out] time_point The time_point to populate.
|
* \param[out] time_point The time_point to populate.
|
||||||
* \return RCL_RET_OK if the last call time was retrieved successfully, or
|
* \return `RCL_RET_OK` if the last call time was retrieved successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -351,30 +382,32 @@ rcl_ret_t
|
||||||
rcl_get_time_point_now(rcl_time_point_t * time_point);
|
rcl_get_time_point_now(rcl_time_point_t * time_point);
|
||||||
|
|
||||||
|
|
||||||
/// Enable the ros time abstraction override.
|
/// Enable the ROS time abstraction override.
|
||||||
/* This method will enable the ros time abstraction override values,
|
/**
|
||||||
|
* This method will enable the ROS time abstraction override values,
|
||||||
* such that the time source will report the set value instead of falling
|
* such that the time source will report the set value instead of falling
|
||||||
* back to system time.
|
* back to system time.
|
||||||
*
|
*
|
||||||
* \param[in] time_source The time_source to enable.
|
* \param[in] time_source The time_source to enable.
|
||||||
* \return RCL_RET_OK if the time source was enabled successfully, or
|
* \return `RCL_RET_OK` if the time source was enabled successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_enable_ros_time_override(rcl_time_source_t * time_source);
|
rcl_enable_ros_time_override(rcl_time_source_t * time_source);
|
||||||
|
|
||||||
/// Disable the ros time abstraction override.
|
/// Disable the ROS time abstraction override.
|
||||||
/* This method will disable the RCL_ROS_TIME time abstraction override values,
|
/**
|
||||||
|
* This method will disable the `RCL_ROS_TIME` time abstraction override values,
|
||||||
* such that the time source will report the system time even if a custom
|
* such that the time source will report the system time even if a custom
|
||||||
* value has been set.
|
* value has been set.
|
||||||
*
|
*
|
||||||
* \param[in] time_source The time_source to disable.
|
* \param[in] time_source The time_source to disable.
|
||||||
* \return RCL_RET_OK if the time source was disabled successfully, or
|
* \return `RCL_RET_OK` if the time source was disabled successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -382,16 +415,17 @@ rcl_ret_t
|
||||||
rcl_disable_ros_time_override(rcl_time_source_t * time_source);
|
rcl_disable_ros_time_override(rcl_time_source_t * time_source);
|
||||||
|
|
||||||
|
|
||||||
/// Check if the RCL_ROS_TIME time source has the override enabled.
|
/// Check if the `RCL_ROS_TIME` time source has the override enabled.
|
||||||
/* This will populate the is_enabled object to indicate if the
|
/**
|
||||||
|
* This will populate the is_enabled object to indicate if the
|
||||||
* time overide is enabled. If it is enabled, the set value will be returned.
|
* time overide is enabled. If it is enabled, the set value will be returned.
|
||||||
* Otherwise this time source will return the equivalent to system time abstraction.
|
* Otherwise this time source will return the equivalent to system time abstraction.
|
||||||
*
|
*
|
||||||
* \param[in] time_source The time_source to query.
|
* \param[in] time_source The time_source to query.
|
||||||
* \param[out] is_enabled Whether the override is enabled..
|
* \param[out] is_enabled Whether the override is enabled..
|
||||||
* \return RCL_RET_OK if the time source was queried successfully, or
|
* \return `RCL_RET_OK` if the time source was queried successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -399,16 +433,18 @@ rcl_ret_t
|
||||||
rcl_is_enabled_ros_time_override(rcl_time_source_t * time_source,
|
rcl_is_enabled_ros_time_override(rcl_time_source_t * time_source,
|
||||||
bool * is_enabled);
|
bool * is_enabled);
|
||||||
|
|
||||||
/// Set the current time for this RCL_ROS_TIME time source.
|
/// Set the current time for this `RCL_ROS_TIME` time source.
|
||||||
/* This function will update the internal storage for the RCL_ROS_TIME time source.
|
/**
|
||||||
|
* This function will update the internal storage for the `RCL_ROS_TIME`
|
||||||
|
* time source.
|
||||||
* If queried and override enabled the time source will return this value,
|
* If queried and override enabled the time source will return this value,
|
||||||
* otherwise it will return the system time.
|
* otherwise it will return the system time.
|
||||||
*
|
*
|
||||||
* \param[in] time_source The time_source to update.
|
* \param[in] time_source The time_source to update.
|
||||||
* \param[in] time_value The new current time.
|
* \param[in] time_value The new current time.
|
||||||
* \return RCL_RET_OK if the time source was set successfully, or
|
* \return `RCL_RET_OK` if the time source was set successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -416,8 +452,9 @@ rcl_ret_t
|
||||||
rcl_set_ros_time_override(rcl_time_source_t * time_source,
|
rcl_set_ros_time_override(rcl_time_source_t * time_source,
|
||||||
rcl_time_point_value_t time_value);
|
rcl_time_point_value_t time_value);
|
||||||
|
|
||||||
/// Retrieve the current time as a rcl_time_point_value_t (an alias for unint64_t).
|
/// Retrieve the current time as a rcl_time_point_value_t.
|
||||||
/* This function returns the time from a system clock.
|
/**
|
||||||
|
* This function returns the time from a system clock.
|
||||||
* The closest equivalent would be to std::chrono::system_clock::now();
|
* The closest equivalent would be to std::chrono::system_clock::now();
|
||||||
*
|
*
|
||||||
* The resolution (e.g. nanoseconds vs microseconds) is not guaranteed.
|
* The resolution (e.g. nanoseconds vs microseconds) is not guaranteed.
|
||||||
|
@ -425,27 +462,30 @@ rcl_set_ros_time_override(rcl_time_source_t * time_source,
|
||||||
* The now argument must point to an allocated rcl_system_time_point_t struct,
|
* The now argument must point to an allocated rcl_system_time_point_t struct,
|
||||||
* as the result is copied into this variable.
|
* as the result is copied into this variable.
|
||||||
*
|
*
|
||||||
* This function may allocate heap memory when an error occurs.
|
* <hr>
|
||||||
* This function is thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free, with an exception on Windows.
|
* ------------------ | -------------
|
||||||
* On Windows this is lock-free if the C11's stdatomic.h function
|
* Allocates Memory | No
|
||||||
* atomic_is_lock_free() returns true for atomic_int_least64_t.
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
|
||||||
*
|
*
|
||||||
* TODO(tfoote): I talked with @wjwwood about possibly promoting this
|
* \todo TODO(tfoote): consider moving this to rmw for more reuse
|
||||||
* method into rmw for more reuse.
|
|
||||||
*
|
*
|
||||||
* \param[out] now a datafield in which the current time is stored
|
* \param[out] now a datafield in which the current time is stored
|
||||||
* \return RCL_RET_OK if the current time was successfully obtained, or
|
* \return `RCL_RET_OK` if the current time was successfully obtained, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_ret_t
|
rcl_ret_t
|
||||||
rcl_system_time_now(rcl_time_point_value_t * now);
|
rcl_system_time_now(rcl_time_point_value_t * now);
|
||||||
|
|
||||||
/// Retrieve the current time as a rcl_time_point_value_t object..
|
/// Retrieve the current time as a rcl_time_point_value_t object.
|
||||||
/* This function returns the time from a monotonically increasing clock.
|
/**
|
||||||
|
* This function returns the time from a monotonically increasing clock.
|
||||||
* The closest equivalent would be to std::chrono::steady_clock::now();
|
* The closest equivalent would be to std::chrono::steady_clock::now();
|
||||||
*
|
*
|
||||||
* The resolution (e.g. nanoseconds vs microseconds) is not guaranteed.
|
* The resolution (e.g. nanoseconds vs microseconds) is not guaranteed.
|
||||||
|
@ -453,19 +493,21 @@ rcl_system_time_now(rcl_time_point_value_t * now);
|
||||||
* The now argument must point to an allocated rcl_time_point_value_t object,
|
* The now argument must point to an allocated rcl_time_point_value_t object,
|
||||||
* as the result is copied into this variable.
|
* as the result is copied into this variable.
|
||||||
*
|
*
|
||||||
* This function may allocate heap memory when an error occurs.
|
* <hr>
|
||||||
* This function is thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free, with an exception on Windows.
|
* ------------------ | -------------
|
||||||
* On Windows this is lock-free if the C11's stdatomic.h function
|
* Allocates Memory | No
|
||||||
* atomic_is_lock_free() returns true for atomic_int_least64_t.
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
|
||||||
*
|
*
|
||||||
* TODO(tfoote) I talked with @wjwwood about possibly promoting this
|
* \todo TODO(tfoote): consider moving this to rmw for more reuse
|
||||||
* method into rmw for more reuse.
|
|
||||||
*
|
*
|
||||||
* \param[out] now a struct in which the current time is stored
|
* \param[out] now a struct in which the current time is stored
|
||||||
* \return RCL_RET_OK if the current time was successfully obtained, or
|
* \return `RCL_RET_OK` if the current time was successfully obtained, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
|
|
@ -30,7 +30,7 @@ extern "C"
|
||||||
|
|
||||||
struct rcl_timer_impl_t;
|
struct rcl_timer_impl_t;
|
||||||
|
|
||||||
/// Handle for a ROS timer.
|
/// Structure which encapsulates a ROS Timer.
|
||||||
typedef struct rcl_timer_t
|
typedef struct rcl_timer_t
|
||||||
{
|
{
|
||||||
/// Private implementation pointer.
|
/// Private implementation pointer.
|
||||||
|
@ -38,12 +38,14 @@ typedef struct rcl_timer_t
|
||||||
} rcl_timer_t;
|
} rcl_timer_t;
|
||||||
|
|
||||||
/// User callback signature for timers.
|
/// User callback signature for timers.
|
||||||
/* The first argument the callback gets is a pointer to the timer.
|
/**
|
||||||
|
* The first argument the callback gets is a pointer to the timer.
|
||||||
* This can be used to cancel the timer, query the time until the next
|
* This can be used to cancel the timer, query the time until the next
|
||||||
* timer callback, exchange the callback with a different one, etc.
|
* timer callback, exchange the callback with a different one, etc.
|
||||||
*
|
*
|
||||||
* The only caveat is that the function rcl_timer_get_time_since_last_call will
|
* The only caveat is that the function rcl_timer_get_time_since_last_call()
|
||||||
* return the time since just before this callback was called, not the last.
|
* will return the time since just before this callback was called, not the
|
||||||
|
* previous call.
|
||||||
* Therefore the second argument given is the time since the previous callback
|
* Therefore the second argument given is the time since the previous callback
|
||||||
* was called, because that information is no longer accessible via the timer.
|
* was called, because that information is no longer accessible via the timer.
|
||||||
* The time since the last callback call is given in nanoseconds.
|
* The time since the last callback call is given in nanoseconds.
|
||||||
|
@ -57,7 +59,8 @@ rcl_timer_t
|
||||||
rcl_get_zero_initialized_timer(void);
|
rcl_get_zero_initialized_timer(void);
|
||||||
|
|
||||||
/// Initialize a timer.
|
/// Initialize a timer.
|
||||||
/* A timer consists of a callback function and a period.
|
/**
|
||||||
|
* A timer consists of a callback function and a period.
|
||||||
* A timer can be added to a wait set and waited on, such that the wait set
|
* A timer can be added to a wait set and waited on, such that the wait set
|
||||||
* will wake up when a timer is ready to be executed.
|
* will wake up when a timer is ready to be executed.
|
||||||
*
|
*
|
||||||
|
@ -75,12 +78,12 @@ rcl_get_zero_initialized_timer(void);
|
||||||
* zero initialized is undefined behavior.
|
* zero initialized is undefined behavior.
|
||||||
*
|
*
|
||||||
* The period is a duration (rather an absolute time in the future).
|
* The period is a duration (rather an absolute time in the future).
|
||||||
* If the period is 0 then it will always be ready.
|
* If the period is `0` then it will always be ready.
|
||||||
*
|
*
|
||||||
* The callback is an optional argument.
|
* The callback is an optional argument.
|
||||||
* Valid inputs are either a pointer to the function callback, or NULL to
|
* Valid inputs are either a pointer to the function callback, or `NULL` to
|
||||||
* indicate that no callback will be stored in rcl.
|
* indicate that no callback will be stored in rcl.
|
||||||
* If the callback is null, the caller client library is responsible for
|
* If the callback is `NULL`, the caller client library is responsible for
|
||||||
* firing the timer callback.
|
* firing the timer callback.
|
||||||
* Else, it must be a function which returns void and takes two arguments,
|
* Else, it must be a function which returns void and takes two arguments,
|
||||||
* the first being a pointer to the associated timer, and the second a uint64_t
|
* the first being a pointer to the associated timer, and the second a uint64_t
|
||||||
|
@ -89,34 +92,45 @@ rcl_get_zero_initialized_timer(void);
|
||||||
*
|
*
|
||||||
* Expected usage:
|
* Expected usage:
|
||||||
*
|
*
|
||||||
* #include <rcl/rcl.h>
|
* ```c
|
||||||
|
* #include <rcl/rcl.h>
|
||||||
*
|
*
|
||||||
* void my_timer_callback(rcl_timer_t * timer, uint64_t last_call_time)
|
* void my_timer_callback(rcl_timer_t * timer, uint64_t last_call_time)
|
||||||
* {
|
* {
|
||||||
* // Do timer work...
|
* // Do timer work...
|
||||||
* // Optionally reconfigure, cancel, or reset the timer...
|
* // Optionally reconfigure, cancel, or reset the timer...
|
||||||
* }
|
* }
|
||||||
*
|
*
|
||||||
* rcl_timer_t timer = rcl_get_zero_initialized_timer();
|
* rcl_timer_t timer = rcl_get_zero_initialized_timer();
|
||||||
* rcl_ret_t ret =
|
* rcl_ret_t ret = rcl_timer_init(
|
||||||
* rcl_timer_init(&timer, RCL_MS_TO_NS(100), my_timer_callback, rcl_get_default_allocator());
|
* &timer, RCL_MS_TO_NS(100), my_timer_callback, rcl_get_default_allocator());
|
||||||
* // ... error handling, use the timer with a wait set, or poll it manually, then cleanup
|
* // ... error handling, use the timer with a wait set, or poll it manually, then cleanup
|
||||||
* ret = rcl_timer_fini(&timer);
|
* ret = rcl_timer_fini(&timer);
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* This function does allocate heap memory.
|
* <hr>
|
||||||
* This function is not thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is not lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1][2][3]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_uintptr_t`</i>
|
||||||
|
*
|
||||||
|
* <i>[2] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t`</i>
|
||||||
|
*
|
||||||
|
* <i>[3] if `atomic_is_lock_free()` returns true for `atomic_bool`</i>
|
||||||
*
|
*
|
||||||
* \param[inout] timer the timer handle to be initialized
|
* \param[inout] timer the timer handle to be initialized
|
||||||
* \param[in] period the duration between calls to the callback in nanoseconds
|
* \param[in] period the duration between calls to the callback in nanoseconds
|
||||||
* \param[in] callback the user defined function to be called every period
|
* \param[in] callback the user defined function to be called every period
|
||||||
* \param[in] allocator the allocator to use for allocations
|
* \param[in] allocator the allocator to use for allocations
|
||||||
* \return RCL_RET_OK if the timer was initialized successfully, or
|
* \return `RCL_RET_OK` if the timer was initialized successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ALREADY_INIT if the timer was already initialized, or
|
* \return `RCL_RET_ALREADY_INIT` if the timer was already initialized, or
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -128,20 +142,30 @@ rcl_timer_init(
|
||||||
rcl_allocator_t allocator);
|
rcl_allocator_t allocator);
|
||||||
|
|
||||||
/// Finalize a timer.
|
/// Finalize a timer.
|
||||||
/* This function will deallocate any memory and make the timer invalid.
|
/**
|
||||||
|
* This function will deallocate any memory and make the timer invalid.
|
||||||
*
|
*
|
||||||
* A timer that is already invalid (zero initialized) or NULL will not fail.
|
* A timer that is already invalid (zero initialized) or `NULL` will not fail.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe with any rcl_timer_* functions used on the
|
* This function is not thread-safe with any rcl_timer_* functions used on the
|
||||||
* same timer object.
|
* same timer object.
|
||||||
*
|
*
|
||||||
* This function may allocate heap memory when an error occurs.
|
* <hr>
|
||||||
* This function is not thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is not lock-free.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1][2][3]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_uintptr_t`</i>
|
||||||
|
*
|
||||||
|
* <i>[2] if `atomic_is_lock_free()` returns true for `atomic_uint_least64_t`</i>
|
||||||
|
*
|
||||||
|
* <i>[3] if `atomic_is_lock_free()` returns true for `atomic_bool`</i>
|
||||||
*
|
*
|
||||||
* \param[inout] timer the handle to the timer to be finalized.
|
* \param[inout] timer the handle to the timer to be finalized.
|
||||||
* \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.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -149,11 +173,12 @@ rcl_ret_t
|
||||||
rcl_timer_fini(rcl_timer_t * timer);
|
rcl_timer_fini(rcl_timer_t * timer);
|
||||||
|
|
||||||
/// Call the timer's callback and set the last call time.
|
/// Call the timer's callback and set the last call time.
|
||||||
/* This function will call the callback and change the last call time even if
|
/**
|
||||||
|
* This function will call the callback and change the last call time even if
|
||||||
* the timer's period has not yet elapsed.
|
* the timer's period has not yet elapsed.
|
||||||
* It is up to the calling code to make sure the period has elapsed by first
|
* It is up to the calling code to make sure the period has elapsed by first
|
||||||
* calling rcl_timer_is_ready().
|
* calling rcl_timer_is_ready().
|
||||||
* If the callback pointer is null (either set in init or exchanged after
|
* If the callback pointer is `NULL` (either set in init or exchanged after
|
||||||
* initialized), no callback is fired.
|
* initialized), no callback is fired.
|
||||||
* However, this function should still be called by the client library to
|
* However, this function should still be called by the client library to
|
||||||
* update the state of the timer.
|
* update the state of the timer.
|
||||||
|
@ -168,18 +193,23 @@ rcl_timer_fini(rcl_timer_t * timer);
|
||||||
* During the callback the timer can be canceled or have its period and/or
|
* During the callback the timer can be canceled or have its period and/or
|
||||||
* callback modified.
|
* callback modified.
|
||||||
*
|
*
|
||||||
* This function may allocate heap memory when an error occurs.
|
* <hr>
|
||||||
* This function is thread-safe, but the user's callback may not be.
|
* Attribute | Adherence
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* ------------------ | -------------
|
||||||
* atomic_is_lock_free() returns true for atomic_int_least64_t, but the user's
|
* Allocates Memory | No
|
||||||
* callback may not be lock-free.
|
* Thread-Safe | Yes [1]
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [2]
|
||||||
|
* <i>[1] user callback might not be thread-safe</i>
|
||||||
|
*
|
||||||
|
* <i>[2] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \param[inout] timer the handle to the timer to call
|
* \param[inout] timer the handle to the timer to call
|
||||||
* \return RCL_RET_OK if the timer was called successfully, or
|
* \return `RCL_RET_OK` if the timer was called successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* \return `RCL_RET_TIMER_INVALID` if the timer is invalid, or
|
||||||
* RCL_RET_TIMER_CANCELED if the timer has been canceled, or
|
* \return `RCL_RET_TIMER_CANCELED` if the timer has been canceled, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -187,24 +217,29 @@ rcl_ret_t
|
||||||
rcl_timer_call(rcl_timer_t * timer);
|
rcl_timer_call(rcl_timer_t * timer);
|
||||||
|
|
||||||
/// Calculates whether or not the timer should be called.
|
/// Calculates whether or not the timer should be called.
|
||||||
/* The result is true if the time until next call is less than, or equal to, 0
|
/**
|
||||||
|
* The result is true if the time until next call is less than, or equal to, 0
|
||||||
* and the timer has not been canceled.
|
* and the timer has not been canceled.
|
||||||
* Otherwise the result is false, indicating the timer should not be called.
|
* Otherwise the result is false, indicating the timer should not be called.
|
||||||
*
|
*
|
||||||
* The is_ready argument must point to an allocated bool object, as the result
|
* The is_ready argument must point to an allocated bool object, as the result
|
||||||
* is copied into it.
|
* is copied into it.
|
||||||
*
|
*
|
||||||
* This function may allocate heap memory when an error occurs.
|
* <hr>
|
||||||
* This function is thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* ------------------ | -------------
|
||||||
* atomic_is_lock_free() returns true for atomic_int_least64_t.
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \param[in] timer the handle to the timer which is being checked
|
* \param[in] timer the handle to the timer which is being checked
|
||||||
* \param[out] is_ready the bool used to store the result of the calculation
|
* \param[out] is_ready the bool used to store the result of the calculation
|
||||||
* \return RCL_RET_OK if the last call time was retrieved successfully, or
|
* \return `RCL_RET_OK` if the last call time was retrieved successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* \return `RCL_RET_TIMER_INVALID` if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -212,7 +247,8 @@ 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);
|
||||||
|
|
||||||
/// Calculate and retrieve the time until the next call in nanoseconds.
|
/// Calculate and retrieve the time until the next call in nanoseconds.
|
||||||
/* This function calculates the time until the next call by adding the timer's
|
/**
|
||||||
|
* This function calculates the time until the next call by adding the timer's
|
||||||
* period to the last call time and subtracting that sum from the current time.
|
* period to the last call time and subtracting that sum from the current time.
|
||||||
* The calculated time until the next call can be positive, indicating that it
|
* The calculated time until the next call can be positive, indicating that it
|
||||||
* is not ready to be called as the period has not elapsed since the last call.
|
* is not ready to be called as the period has not elapsed since the last call.
|
||||||
|
@ -221,20 +257,24 @@ rcl_timer_is_ready(const rcl_timer_t * timer, bool * is_ready);
|
||||||
* should be called.
|
* should be called.
|
||||||
* A negative value indicates the timer call is overdue by that amount.
|
* A negative value indicates the timer call is overdue by that amount.
|
||||||
*
|
*
|
||||||
* The time_until_next_call argument must point to an allocated int64_t, as the
|
* The `time_until_next_call` argument must point to an allocated int64_t, as
|
||||||
* the time until is coped into that instance.
|
* the time until is copied into that instance.
|
||||||
*
|
*
|
||||||
* This function may allocate heap memory when an error occurs.
|
* <hr>
|
||||||
* This function is thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* ------------------ | -------------
|
||||||
* atomic_is_lock_free() returns true for atomic_int_least64_t.
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \param[in] timer the handle to the timer that is being queried
|
* \param[in] timer the handle to the timer that is being queried
|
||||||
* \param[out] time_until_next_call the output variable for the result
|
* \param[out] time_until_next_call the output variable for the result
|
||||||
* \return RCL_RET_OK if the timer until next call was successfully calculated, or
|
* \return `RCL_RET_OK` if the timer until next call was successfully calculated, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* \return `RCL_RET_TIMER_INVALID` if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -242,7 +282,8 @@ 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);
|
||||||
|
|
||||||
/// Retrieve the time since the previous call to rcl_timer_call() occurred.
|
/// Retrieve the time since the previous call to rcl_timer_call() occurred.
|
||||||
/* This function calculates the time since the last call and copies it into
|
/**
|
||||||
|
* This function calculates the time since the last call and copies it into
|
||||||
* the given uint64_t variable.
|
* the given uint64_t variable.
|
||||||
*
|
*
|
||||||
* Calling this function within a callback will not return the time since the
|
* Calling this function within a callback will not return the time since the
|
||||||
|
@ -251,17 +292,21 @@ rcl_timer_get_time_until_next_call(const rcl_timer_t * timer, int64_t * time_unt
|
||||||
* The time_since_last_call argument must be a pointer to an already allocated
|
* The time_since_last_call argument must be a pointer to an already allocated
|
||||||
* uint64_t.
|
* uint64_t.
|
||||||
*
|
*
|
||||||
* This function may allocate heap memory when an error occurs.
|
* <hr>
|
||||||
* This function is thread-safe.
|
* Attribute | Adherence
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* ------------------ | -------------
|
||||||
* atomic_is_lock_free() returns true for atomic_int_least64_t.
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \param[in] timer the handle to the timer which is being queried
|
* \param[in] timer the handle to the timer which is being queried
|
||||||
* \param[out] time_since_last_call the struct in which the time is stored
|
* \param[out] time_since_last_call the struct in which the time is stored
|
||||||
* \return RCL_RET_OK if the last call time was retrieved successfully, or
|
* \return `RCL_RET_OK` if the last call time was retrieved successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* \return `RCL_RET_TIMER_INVALID` if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -269,20 +314,26 @@ 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);
|
||||||
|
|
||||||
/// Retrieve the period of the timer.
|
/// Retrieve the period of the timer.
|
||||||
/* This function retrieves the period and copies it into the give variable.
|
/**
|
||||||
|
* This function retrieves the period and copies it into the give variable.
|
||||||
*
|
*
|
||||||
* The period argument must be a pointer to an already allocated uint64_t.
|
* The period argument must be a pointer to an already allocated uint64_t.
|
||||||
*
|
*
|
||||||
* This function is thread-safe.
|
* <hr>
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* Attribute | Adherence
|
||||||
* atomic_is_lock_free() returns true for atomic_int_least64_t.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \param[in] timer the handle to the timer which is being queried
|
* \param[in] timer the handle to the timer which is being queried
|
||||||
* \param[out] period the uint64_t in which the period is stored
|
* \param[out] period the uint64_t in which the period is stored
|
||||||
* \return RCL_RET_OK if the period was retrieved successfully, or
|
* \return `RCL_RET_OK` if the period was retrieved successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* \return `RCL_RET_TIMER_INVALID` if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -290,24 +341,30 @@ 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);
|
||||||
|
|
||||||
/// Exchange the period of the timer and return the previous period.
|
/// Exchange the period of the timer and return the previous period.
|
||||||
/* This function exchanges the period in the timer and copies the old one into
|
/**
|
||||||
|
* This function exchanges the period in the timer and copies the old one into
|
||||||
* the give variable.
|
* the give variable.
|
||||||
*
|
*
|
||||||
* Exchanging (changing) the period will not affect already waiting wait sets.
|
* Exchanging (changing) the period will not affect already waiting wait sets.
|
||||||
*
|
*
|
||||||
* The old_period argument must be a pointer to an already allocated uint64_t.
|
* The old_period argument must be a pointer to an already allocated uint64_t.
|
||||||
*
|
*
|
||||||
* This function is thread-safe.
|
* <hr>
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* Attribute | Adherence
|
||||||
* atomic_is_lock_free() returns true for atomic_int_least64_t.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \param[in] timer the handle to the timer which is being modified
|
* \param[in] timer the handle to the timer which is being modified
|
||||||
* \param[out] new_period the uint64_t to exchange into the timer
|
* \param[out] new_period the uint64_t to exchange into the timer
|
||||||
* \param[out] old_period the uint64_t in which the previous period is stored
|
* \param[out] old_period the uint64_t in which the previous period is stored
|
||||||
* \return RCL_RET_OK if the period was retrieved successfully, or
|
* \return `RCL_RET_OK` if the period was retrieved successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* \return `RCL_RET_TIMER_INVALID` if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -315,16 +372,22 @@ 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);
|
||||||
|
|
||||||
/// Return the current timer callback.
|
/// Return the current timer callback.
|
||||||
/* This function can fail, and therefore return NULL, if:
|
/**
|
||||||
* - timer is NULL
|
* This function can fail, and therefore return `NULL`, if:
|
||||||
|
* - timer is `NULL`
|
||||||
* - timer has not been initialized (the implementation is invalid)
|
* - timer has not been initialized (the implementation is invalid)
|
||||||
*
|
*
|
||||||
* This function is thread-safe.
|
* <hr>
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* Attribute | Adherence
|
||||||
* atomic_is_lock_free() returns true for atomic_uintptr_t.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \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_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -332,20 +395,26 @@ rcl_timer_callback_t
|
||||||
rcl_timer_get_callback(const rcl_timer_t * timer);
|
rcl_timer_get_callback(const rcl_timer_t * timer);
|
||||||
|
|
||||||
/// Exchange the current timer callback and return the current callback.
|
/// Exchange the current timer callback and return the current callback.
|
||||||
/* This function can fail, and therefore return NULL, if:
|
/**
|
||||||
* - timer is NULL
|
* This function can fail, and therefore return `NULL`, if:
|
||||||
|
* - timer is `NULL`
|
||||||
* - timer has not been initialized (the implementation is invalid)
|
* - timer has not been initialized (the implementation is invalid)
|
||||||
*
|
*
|
||||||
* This function can set callback to null, in which case the callback is
|
* This function can set callback to `NULL`, in which case the callback is
|
||||||
* ignored when rcl_timer_call is called.
|
* ignored when rcl_timer_call is called.
|
||||||
*
|
*
|
||||||
* This function is thread-safe.
|
* <hr>
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* Attribute | Adherence
|
||||||
* atomic_is_lock_free() returns true for atomic_uintptr_t.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \param[inout] timer handle to the timer from the callback should be exchanged
|
* \param[inout] timer handle to the timer from the callback should be exchanged
|
||||||
* \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_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -353,21 +422,27 @@ 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);
|
||||||
|
|
||||||
/// Cancel a timer.
|
/// Cancel a timer.
|
||||||
/* When a timer is canceled, rcl_timer_is_ready() will return false for that
|
/**
|
||||||
|
* When a timer is canceled, rcl_timer_is_ready() will return false for that
|
||||||
* timer, and rcl_timer_call() will fail with RCL_RET_TIMER_CANCELED.
|
* timer, and rcl_timer_call() will fail with RCL_RET_TIMER_CANCELED.
|
||||||
*
|
*
|
||||||
* A canceled timer can be reset with rcl_timer_reset(), and then used again.
|
* A canceled timer can be reset with rcl_timer_reset(), and then used again.
|
||||||
* Calling this function on an already canceled timer will succeed.
|
* Calling this function on an already canceled timer will succeed.
|
||||||
*
|
*
|
||||||
* This function is thread-safe.
|
* <hr>
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* Attribute | Adherence
|
||||||
* atomic_is_lock_free() returns true for atomic_bool.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \param[inout] timer the timer to be canceled
|
* \param[inout] timer the timer to be canceled
|
||||||
* \return RCL_RET_OK if the last call time was retrieved successfully, or
|
* \return `RCL_RET_OK` if the last call time was retrieved successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* \return `RCL_RET_TIMER_INVALID` if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -375,21 +450,28 @@ rcl_ret_t
|
||||||
rcl_timer_cancel(rcl_timer_t * timer);
|
rcl_timer_cancel(rcl_timer_t * timer);
|
||||||
|
|
||||||
/// Retrieve the canceled state of a timer.
|
/// Retrieve the canceled state of a timer.
|
||||||
/* If the timer is canceled true will be stored in the is_canceled argument.
|
/**
|
||||||
|
* If the timer is canceled true will be stored in the is_canceled argument.
|
||||||
* Otherwise false will be stored in the is_canceled argument.
|
* Otherwise false will be stored in the is_canceled argument.
|
||||||
*
|
*
|
||||||
* The is_canceled argument must point to an allocated bool, as the result is
|
* The is_canceled argument must point to an allocated bool, as the result is
|
||||||
* copied into this variable.
|
* copied into this variable.
|
||||||
*
|
*
|
||||||
* This function is thread-safe.
|
* <hr>
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* Attribute | Adherence
|
||||||
* atomic_is_lock_free() returns true for atomic_bool.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_bool`</i>
|
||||||
*
|
*
|
||||||
* \param[in] timer the timer to be queried
|
* \param[in] timer the timer to be queried
|
||||||
* \return RCL_RET_OK if the last call time was retrieved successfully, or
|
* \param[out] is_canceled storage for the is canceled bool
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_OK` if the last call time was retrieved successfully, or
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_TIMER_INVALID` if the timer is invalid, or
|
||||||
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -397,19 +479,25 @@ 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);
|
||||||
|
|
||||||
/// Reset a timer.
|
/// Reset a timer.
|
||||||
/* This function can be called on a timer, canceled or not.
|
/**
|
||||||
|
* This function can be called on a timer, canceled or not.
|
||||||
* For all timers it will reset the last call time to now.
|
* For all timers it will reset the last call time to now.
|
||||||
* For canceled timers it will additionally make the timer not canceled.
|
* For canceled timers it will additionally make the timer not canceled.
|
||||||
*
|
*
|
||||||
* This function is thread-safe.
|
* <hr>
|
||||||
* This function is lock-free so long as the C11's stdatomic.h function
|
* Attribute | Adherence
|
||||||
* atomic_is_lock_free() returns true for atomic_int_least64_t.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | Yes
|
||||||
|
* Uses Atomics | Yes
|
||||||
|
* Lock-Free | Yes [1]
|
||||||
|
* <i>[1] if `atomic_is_lock_free()` returns true for `atomic_int_least64_t`</i>
|
||||||
*
|
*
|
||||||
* \param[inout] timer the timer to be reset
|
* \param[inout] timer the timer to be reset
|
||||||
* \return RCL_RET_OK if the last call time was retrieved successfully, or
|
* \return `RCL_RET_OK` if the last call time was retrieved successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_TIMER_INVALID if the timer is invalid, or
|
* \return `RCL_RET_TIMER_INVALID` if the timer is invalid, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
|
|
@ -18,35 +18,65 @@
|
||||||
#include <rmw/types.h>
|
#include <rmw/types.h>
|
||||||
|
|
||||||
typedef rmw_ret_t rcl_ret_t;
|
typedef rmw_ret_t rcl_ret_t;
|
||||||
|
/// Success return code.
|
||||||
#define RCL_RET_OK RMW_RET_OK
|
#define RCL_RET_OK RMW_RET_OK
|
||||||
|
/// Unspecified error return code.
|
||||||
#define RCL_RET_ERROR RMW_RET_ERROR
|
#define RCL_RET_ERROR RMW_RET_ERROR
|
||||||
|
/// Timeout occurred return code.
|
||||||
#define RCL_RET_TIMEOUT RMW_RET_TIMEOUT
|
#define RCL_RET_TIMEOUT RMW_RET_TIMEOUT
|
||||||
|
|
||||||
// rcl specific ret codes start at 100
|
// rcl specific ret codes start at 100
|
||||||
|
/// rcl_init() already called return code.
|
||||||
#define RCL_RET_ALREADY_INIT 100
|
#define RCL_RET_ALREADY_INIT 100
|
||||||
|
/// rcl_init() not yet called return code.
|
||||||
#define RCL_RET_NOT_INIT 101
|
#define RCL_RET_NOT_INIT 101
|
||||||
|
/// Failed to allocate memory return code.
|
||||||
#define RCL_RET_BAD_ALLOC 102
|
#define RCL_RET_BAD_ALLOC 102
|
||||||
|
/// Invalid argument return code.
|
||||||
#define RCL_RET_INVALID_ARGUMENT 103
|
#define RCL_RET_INVALID_ARGUMENT 103
|
||||||
|
/// Mismatched rmw identifier return code.
|
||||||
#define RCL_RET_MISMATCHED_RMW_ID 104
|
#define RCL_RET_MISMATCHED_RMW_ID 104
|
||||||
|
|
||||||
// rcl node specific ret codes in 2XX
|
// rcl node specific ret codes in 2XX
|
||||||
|
/// Invalid rcl_node_t given return code.
|
||||||
#define RCL_RET_NODE_INVALID 200
|
#define RCL_RET_NODE_INVALID 200
|
||||||
|
|
||||||
// rcl publisher specific ret codes in 3XX
|
// rcl publisher specific ret codes in 3XX
|
||||||
|
/// Invalid rcl_publisher_t given return code.
|
||||||
#define RCL_RET_PUBLISHER_INVALID 300
|
#define RCL_RET_PUBLISHER_INVALID 300
|
||||||
|
|
||||||
// rcl subscription specific ret codes in 4XX
|
// rcl subscription specific ret codes in 4XX
|
||||||
|
/// Invalid rcl_subscription_t given return code.
|
||||||
#define RCL_RET_SUBSCRIPTION_INVALID 400
|
#define RCL_RET_SUBSCRIPTION_INVALID 400
|
||||||
|
/// Failed to take a message from the subscription return code.
|
||||||
#define RCL_RET_SUBSCRIPTION_TAKE_FAILED 401
|
#define RCL_RET_SUBSCRIPTION_TAKE_FAILED 401
|
||||||
|
|
||||||
// rcl service client specific ret codes in 5XX
|
// rcl service client specific ret codes in 5XX
|
||||||
|
/// Invalid rcl_client_t given return code.
|
||||||
#define RCL_RET_CLIENT_INVALID 500
|
#define RCL_RET_CLIENT_INVALID 500
|
||||||
|
/// Failed to take a response from the client return code.
|
||||||
#define RCL_RET_CLIENT_TAKE_FAILED 501
|
#define RCL_RET_CLIENT_TAKE_FAILED 501
|
||||||
|
|
||||||
// rcl service server specific ret codes in 6XX
|
// rcl service server specific ret codes in 6XX
|
||||||
|
/// Invalid rcl_service_t given return code.
|
||||||
#define RCL_RET_SERVICE_INVALID 600
|
#define RCL_RET_SERVICE_INVALID 600
|
||||||
|
/// Failed to take a request from the service return code.
|
||||||
#define RCL_RET_SERVICE_TAKE_FAILED 601
|
#define RCL_RET_SERVICE_TAKE_FAILED 601
|
||||||
|
|
||||||
// rcl guard condition specific ret codes in 7XX
|
// rcl guard condition specific ret codes in 7XX
|
||||||
|
|
||||||
// rcl timer specific ret codes in 8XX
|
// rcl timer specific ret codes in 8XX
|
||||||
|
/// Invalid rcl_timer_t given return code.
|
||||||
#define RCL_RET_TIMER_INVALID 800
|
#define RCL_RET_TIMER_INVALID 800
|
||||||
|
/// Given timer was canceled return code.
|
||||||
#define RCL_RET_TIMER_CANCELED 801
|
#define RCL_RET_TIMER_CANCELED 801
|
||||||
|
|
||||||
// rcl wait and wait set specific ret codes in 9XX
|
// rcl wait and wait set specific ret codes in 9XX
|
||||||
|
/// Invalid rcl_wait_set_t given return code.
|
||||||
#define RCL_RET_WAIT_SET_INVALID 900
|
#define RCL_RET_WAIT_SET_INVALID 900
|
||||||
|
/// Given rcl_wait_set_t is empty return code.
|
||||||
#define RCL_RET_WAIT_SET_EMPTY 901
|
#define RCL_RET_WAIT_SET_EMPTY 901
|
||||||
|
/// Given rcl_wait_set_t is full return code.
|
||||||
#define RCL_RET_WAIT_SET_FULL 902
|
#define RCL_RET_WAIT_SET_FULL 902
|
||||||
|
|
||||||
#endif // RCL__TYPES_H_
|
#endif // RCL__TYPES_H_
|
||||||
|
|
|
@ -56,19 +56,20 @@ typedef struct rcl_wait_set_t
|
||||||
struct rcl_wait_set_impl_t * impl;
|
struct rcl_wait_set_impl_t * impl;
|
||||||
} 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_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
rcl_wait_set_t
|
rcl_wait_set_t
|
||||||
rcl_get_zero_initialized_wait_set(void);
|
rcl_get_zero_initialized_wait_set(void);
|
||||||
|
|
||||||
/// Initialize a rcl wait set with space for items to be waited on.
|
/// Initialize a rcl wait set with space for items to be waited on.
|
||||||
/* This function allocates space for the subscriptions and other wait-able
|
/**
|
||||||
|
* This function allocates space for the subscriptions and other wait-able
|
||||||
* entities that can be stored in the wait set.
|
* entities that can be stored in the wait set.
|
||||||
* It also sets the allocator to the given allocator and initializes the pruned
|
* It also sets the allocator to the given allocator and initializes the pruned
|
||||||
* member to be false.
|
* member to be false.
|
||||||
*
|
*
|
||||||
* The wait_set struct should be allocated and initialized to NULL.
|
* The wait_set struct should be allocated and initialized to `NULL`.
|
||||||
* If the wait_set is allocated but the memory is uninitialized the behavior is
|
* If the wait_set is allocated but the memory is uninitialized the behavior is
|
||||||
* undefined.
|
* undefined.
|
||||||
* Calling this function on a wait set that has already been initialized will
|
* Calling this function on a wait set that has already been initialized will
|
||||||
|
@ -79,17 +80,23 @@ rcl_get_zero_initialized_wait_set(void);
|
||||||
*
|
*
|
||||||
* Expected usage:
|
* Expected usage:
|
||||||
*
|
*
|
||||||
* #include <rcl/wait.h>
|
* ```c
|
||||||
|
* #include <rcl/wait.h>
|
||||||
*
|
*
|
||||||
* rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
|
* rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
|
||||||
* rcl_ret_t ret = rcl_wait_set_init(&wait_set, 42, 42, rcl_get_default_allocator());
|
* rcl_ret_t ret = rcl_wait_set_init(&wait_set, 42, 42, rcl_get_default_allocator());
|
||||||
* // ... error handling, then use it, then call the matching fini:
|
* // ... error handling, then use it, then call the matching fini:
|
||||||
* ret = rcl_wait_set_fini(&wait_set);
|
* ret = rcl_wait_set_fini(&wait_set);
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* This function is thread-safe for different wait_set objects.
|
* <hr>
|
||||||
* Thread-safety of this function requires a thread-safe allocator if the
|
* Attribute | Adherence
|
||||||
* allocator is shared with other parts of the system.
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] wait_set the wait set struct to be initialized
|
* \param[inout] wait_set the wait set struct to be initialized
|
||||||
* \param[in] number_of_subscriptions non-zero size of the subscriptions set
|
* \param[in] number_of_subscriptions non-zero size of the subscriptions set
|
||||||
|
@ -98,11 +105,11 @@ rcl_get_zero_initialized_wait_set(void);
|
||||||
* \param[in] number_of_clients non-zero size of the clients set
|
* \param[in] number_of_clients non-zero size of the clients set
|
||||||
* \param[in] number_of_services non-zero size of the services set
|
* \param[in] number_of_services non-zero size of the services set
|
||||||
* \param[in] allocator the allocator to use when allocating space in the sets
|
* \param[in] allocator the allocator to use when allocating space in the sets
|
||||||
* \return RCL_RET_OK if the wait set is initialized successfully, or
|
* \return `RCL_RET_OK` if the wait set is initialized successfully, or
|
||||||
* RCL_RET_ALREADY_INIT if the wait set is not zero initialized, or
|
* \return `RCL_RET_ALREADY_INIT` if the wait set is not zero initialized, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -117,7 +124,8 @@ rcl_wait_set_init(
|
||||||
rcl_allocator_t allocator);
|
rcl_allocator_t allocator);
|
||||||
|
|
||||||
/// Finalize a rcl wait set.
|
/// Finalize a rcl wait set.
|
||||||
/* Deallocates any memory in the wait set that was allocated in
|
/**
|
||||||
|
* Deallocates any memory in the wait set that was allocated in
|
||||||
* rcl_wait_set_init() using the allocator given in the initialization.
|
* rcl_wait_set_init() using the allocator given in the initialization.
|
||||||
*
|
*
|
||||||
* Calling this function on a zero initialized wait set will do nothing and
|
* Calling this function on a zero initialized wait set will do nothing and
|
||||||
|
@ -127,13 +135,18 @@ rcl_wait_set_init(
|
||||||
* and so calling this function or rcl_wait_set_init() immediately after will
|
* and so calling this function or rcl_wait_set_init() immediately after will
|
||||||
* succeed.
|
* succeed.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
* This function is lock-free.
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] wait_set the wait set struct to be finalized.
|
* \param[inout] wait_set the wait set struct to be finalized.
|
||||||
* \return RCL_RET_OK if the finalization was successful, or
|
* \return `RCL_RET_OK` if the finalization was successful, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -141,17 +154,23 @@ rcl_ret_t
|
||||||
rcl_wait_set_fini(rcl_wait_set_t * wait_set);
|
rcl_wait_set_fini(rcl_wait_set_t * wait_set);
|
||||||
|
|
||||||
/// Retrieve the wait set's allocator.
|
/// Retrieve the wait set's allocator.
|
||||||
/* The allocator must be an allocated rcl_allocator_t struct, as the result is
|
/**
|
||||||
|
* The allocator must be an allocated rcl_allocator_t struct, as the result is
|
||||||
* copied into this variable.
|
* copied into this variable.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
* This function is lock-free.
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[in] wait_set the handle to the wait set
|
* \param[in] wait_set the handle to the wait set
|
||||||
* \param[out] allocator the rcl_allocator_t struct to which the result is copied
|
* \param[out] allocator the rcl_allocator_t struct to which the result is copied
|
||||||
* \return RCL_RET_OK if the allocator was successfully retrieved, or
|
* \return `RCL_RET_OK` if the allocator was successfully retrieved, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -159,22 +178,28 @@ 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);
|
||||||
|
|
||||||
/// Store a pointer to the given subscription in the next empty spot in the set.
|
/// Store a pointer to the given subscription in the next empty spot in the set.
|
||||||
/* This function does not guarantee that the subscription is not already in the
|
/**
|
||||||
|
* This function does not guarantee that the subscription is not already in the
|
||||||
* wait set.
|
* wait set.
|
||||||
*
|
*
|
||||||
* Also add the rmw representation to the underlying rmw array and increment
|
* Also add the rmw representation to the underlying rmw array and increment
|
||||||
* the rmw array count.
|
* the rmw array count.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
* This function is lock-free.
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] wait_set struct in which the subscription is to be stored
|
* \param[inout] wait_set struct in which the subscription is to be stored
|
||||||
* \param[in] subscription the subscription to be added to the wait set
|
* \param[in] subscription the subscription to be added to the wait set
|
||||||
* \return RCL_RET_OK if added successfully, or
|
* \return `RCL_RET_OK` if added successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_WAIT_SET_INVALID if the wait set is zero initialized, or
|
* \return `RCL_RET_WAIT_SET_INVALID` if the wait set is zero initialized, or
|
||||||
* RCL_RET_WAIT_SET_FULL if the subscription set is full, or
|
* \return `RCL_RET_WAIT_SET_FULL` if the subscription set is full, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -183,22 +208,28 @@ rcl_wait_set_add_subscription(
|
||||||
rcl_wait_set_t * wait_set,
|
rcl_wait_set_t * wait_set,
|
||||||
const rcl_subscription_t * subscription);
|
const rcl_subscription_t * subscription);
|
||||||
|
|
||||||
/// Remove (sets to NULL) the subscriptions in the wait set.
|
/// Remove (sets to `NULL`) the subscriptions in the wait set.
|
||||||
/* This function should be used after passing using rcl_wait, but before
|
/**
|
||||||
|
* This function should be used after passing using rcl_wait, but before
|
||||||
* adding new subscriptions to the set.
|
* adding new subscriptions to the set.
|
||||||
* Sets all of the entries in the underlying rmw array to null, and sets the
|
* Sets all of the entries in the underlying rmw array to `NULL`, and sets the
|
||||||
* count in the rmw array to 0.
|
* count in the rmw array to `0`.
|
||||||
*
|
*
|
||||||
* Calling this on an uninitialized (zero initialized) wait set will fail.
|
* Calling this on an uninitialized (zero initialized) wait set will fail.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
* This function is lock-free.
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | No
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] wait_set struct to have its subscriptions cleared
|
* \param[inout] wait_set struct to have its subscriptions cleared
|
||||||
* \return RCL_RET_OK if cleared successfully, or
|
* \return `RCL_RET_OK` if cleared successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_WAIT_SET_INVALID if the wait set is zero initialized, or
|
* \return `RCL_RET_WAIT_SET_INVALID` if the wait set is zero initialized, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -206,31 +237,38 @@ 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);
|
||||||
|
|
||||||
/// Reallocate space for the subscriptions in the wait set.
|
/// Reallocate space for the subscriptions in the wait set.
|
||||||
/* This function will deallocate and reallocate the memory for the
|
/**
|
||||||
|
* This function will deallocate and reallocate the memory for the
|
||||||
* subscriptions set.
|
* subscriptions set.
|
||||||
*
|
*
|
||||||
* A size of 0 will just deallocate the memory and assign NULL to the array.
|
* A size of 0 will just deallocate the memory and assign `NULL` to the array.
|
||||||
*
|
*
|
||||||
* Allocation and deallocation is done with the allocator given during the
|
* Allocation and deallocation is done with the allocator given during the
|
||||||
* wait set's initialization.
|
* wait set's initialization.
|
||||||
*
|
*
|
||||||
* After calling this function all values in the set will be set to NULL,
|
* After calling this function all values in the set will be set to `NULL`,
|
||||||
* effectively the same as calling rcl_wait_set_clear_subscriptions().
|
* effectively the same as calling rcl_wait_set_clear_subscriptions().
|
||||||
* Similarly, the underlying rmw representation is reallocated and reset:
|
* Similarly, the underlying rmw representation is reallocated and reset:
|
||||||
* all entries are set to null and the count is set to zero.
|
* all entries are set to `NULL` and the count is set to zero.
|
||||||
*
|
*
|
||||||
* If the requested size matches the current size, no allocation will be done.
|
* If the requested size matches the current size, no allocation will be done.
|
||||||
*
|
*
|
||||||
* This can be called on an uninitialized (zero initialized) wait set.
|
* This can be called on an uninitialized (zero initialized) wait set.
|
||||||
*
|
*
|
||||||
* This function is not thread-safe.
|
* <hr>
|
||||||
|
* Attribute | Adherence
|
||||||
|
* ------------------ | -------------
|
||||||
|
* Allocates Memory | Yes
|
||||||
|
* Thread-Safe | No
|
||||||
|
* Uses Atomics | No
|
||||||
|
* Lock-Free | Yes
|
||||||
*
|
*
|
||||||
* \param[inout] wait_set struct to have its subscriptions cleared
|
* \param[inout] wait_set struct to have its subscriptions cleared
|
||||||
* \param[in] size a size for the new set
|
* \param[in] size a size for the new set
|
||||||
* \return RCL_RET_OK if resized successfully, or
|
* \return `RCL_RET_OK` if resized successfully, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_BAD_ALLOC if allocating memory failed, or
|
* \return `RCL_RET_BAD_ALLOC` if allocating memory failed, or
|
||||||
* RCL_RET_ERROR if an unspecified error occurs.
|
* \return `RCL_RET_ERROR` if an unspecified error occurs.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
@ -238,7 +276,8 @@ 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);
|
||||||
|
|
||||||
/// Store a pointer to the guard condition in the next empty spot in the set.
|
/// Store a pointer to the guard condition in the next empty spot in the set.
|
||||||
/* 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_PUBLIC
|
||||||
|
@ -248,8 +287,9 @@ rcl_wait_set_add_guard_condition(
|
||||||
rcl_wait_set_t * wait_set,
|
rcl_wait_set_t * wait_set,
|
||||||
const rcl_guard_condition_t * guard_condition);
|
const rcl_guard_condition_t * guard_condition);
|
||||||
|
|
||||||
/// Remove (sets to NULL) the guard conditions in the wait set.
|
/// Remove (sets to `NULL`) the guard conditions in the wait set.
|
||||||
/* 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_PUBLIC
|
||||||
|
@ -258,7 +298,8 @@ 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);
|
||||||
|
|
||||||
/// Reallocate space for the guard conditions in the wait set.
|
/// Reallocate space for the guard conditions in the 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_PUBLIC
|
||||||
|
@ -267,7 +308,8 @@ 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);
|
||||||
|
|
||||||
/// Store a pointer to the timer in the next empty spot in the set.
|
/// Store a pointer to the timer in the next empty spot in the set.
|
||||||
/* 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_PUBLIC
|
||||||
|
@ -277,8 +319,9 @@ rcl_wait_set_add_timer(
|
||||||
rcl_wait_set_t * wait_set,
|
rcl_wait_set_t * wait_set,
|
||||||
const rcl_timer_t * timer);
|
const rcl_timer_t * timer);
|
||||||
|
|
||||||
/// Remove (sets to NULL) the timers in the wait set.
|
/// Remove (sets to `NULL`) the timers in the wait set.
|
||||||
/* 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_PUBLIC
|
||||||
|
@ -287,7 +330,8 @@ 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);
|
||||||
|
|
||||||
/// Reallocate space for the timers in the wait set.
|
/// Reallocate space for the timers in the 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_PUBLIC
|
||||||
|
@ -296,7 +340,8 @@ 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);
|
||||||
|
|
||||||
/// Store a pointer to the client in the next empty spot in the set.
|
/// Store a pointer to the client in the next empty spot in the set.
|
||||||
/* 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_PUBLIC
|
||||||
|
@ -306,8 +351,9 @@ rcl_wait_set_add_client(
|
||||||
rcl_wait_set_t * wait_set,
|
rcl_wait_set_t * wait_set,
|
||||||
const rcl_client_t * client);
|
const rcl_client_t * client);
|
||||||
|
|
||||||
/// Remove (sets to NULL) the clients in the wait set.
|
/// Remove (sets to `NULL`) the clients in the wait set.
|
||||||
/* 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_PUBLIC
|
||||||
|
@ -316,7 +362,8 @@ rcl_ret_t
|
||||||
rcl_wait_set_clear_clients(rcl_wait_set_t * wait_set);
|
rcl_wait_set_clear_clients(rcl_wait_set_t * wait_set);
|
||||||
|
|
||||||
/// Reallocate space for the clients in the wait set.
|
/// Reallocate space for the clients in the 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_PUBLIC
|
||||||
|
@ -325,7 +372,8 @@ rcl_ret_t
|
||||||
rcl_wait_set_resize_clients(rcl_wait_set_t * wait_set, size_t size);
|
rcl_wait_set_resize_clients(rcl_wait_set_t * wait_set, size_t size);
|
||||||
|
|
||||||
/// Store a pointer to the client in the next empty spot in the set.
|
/// Store a pointer to the client in the next empty spot in the set.
|
||||||
/* 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_PUBLIC
|
||||||
|
@ -335,8 +383,9 @@ rcl_wait_set_add_service(
|
||||||
rcl_wait_set_t * wait_set,
|
rcl_wait_set_t * wait_set,
|
||||||
const rcl_service_t * service);
|
const rcl_service_t * service);
|
||||||
|
|
||||||
/// Remove (sets to NULL) the services in the wait set.
|
/// Remove (sets to `NULL`) the services in the wait set.
|
||||||
/* 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_PUBLIC
|
||||||
|
@ -345,7 +394,8 @@ rcl_ret_t
|
||||||
rcl_wait_set_clear_services(rcl_wait_set_t * wait_set);
|
rcl_wait_set_clear_services(rcl_wait_set_t * wait_set);
|
||||||
|
|
||||||
/// Reallocate space for the services in the wait set.
|
/// Reallocate space for the services in the 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_PUBLIC
|
||||||
|
@ -354,66 +404,69 @@ rcl_ret_t
|
||||||
rcl_wait_set_resize_services(rcl_wait_set_t * wait_set, size_t size);
|
rcl_wait_set_resize_services(rcl_wait_set_t * wait_set, size_t size);
|
||||||
|
|
||||||
/// Block until the wait set is ready or until the timeout has been exceeded.
|
/// Block until the wait set is ready or until the timeout has been exceeded.
|
||||||
/* This function will collect the items in the rcl_wait_set_t and pass them
|
/**
|
||||||
|
* This function will collect the items in the rcl_wait_set_t and pass them
|
||||||
* to the underlying rmw_wait function.
|
* to the underlying rmw_wait function.
|
||||||
*
|
*
|
||||||
* The items in the wait set will be either left untouched or set to NULL after
|
* The items in the wait set will be either left untouched or set to `NULL` after
|
||||||
* this function returns.
|
* this function returns.
|
||||||
* Items that are not NULL are ready, where ready means different things based
|
* Items that are not `NULL` are ready, where ready means different things based
|
||||||
* on the type of the item.
|
* on the type of the item.
|
||||||
* For subscriptions this means there are messages that can be taken.
|
* For subscriptions this means there are messages that can be taken.
|
||||||
* For guard conditions this means the guard condition was triggered.
|
* For guard conditions this means the guard condition was triggered.
|
||||||
*
|
*
|
||||||
* Expected usage:
|
* Expected usage:
|
||||||
*
|
*
|
||||||
* #include <rcl/rcl.h>
|
* ```c
|
||||||
|
* #include <rcl/rcl.h>
|
||||||
*
|
*
|
||||||
* // rcl_init() called successfully before here...
|
* // rcl_init() called successfully before here...
|
||||||
* rcl_node_t node; // initialize this, see rcl_node_init()
|
* rcl_node_t node; // initialize this, see rcl_node_init()
|
||||||
* rcl_subscription_t sub1; // initialize this, see rcl_subscription_init()
|
* rcl_subscription_t sub1; // initialize this, see rcl_subscription_init()
|
||||||
* rcl_subscription_t sub2; // initialize this, see rcl_subscription_init()
|
* rcl_subscription_t sub2; // initialize this, see rcl_subscription_init()
|
||||||
* rcl_guard_condition_t gc1; // initialize this, see rcl_guard_condition_init()
|
* rcl_guard_condition_t gc1; // initialize this, see rcl_guard_condition_init()
|
||||||
* rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
|
* rcl_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
|
||||||
* rcl_ret_t ret = rcl_wait_set_init(&wait_set, 2, 1, 0, rcl_get_default_allocator());
|
* rcl_ret_t ret = rcl_wait_set_init(&wait_set, 2, 1, 0, rcl_get_default_allocator());
|
||||||
|
* // ... error handling
|
||||||
|
* do {
|
||||||
|
* ret = rcl_wait_set_clear_subscriptions(&wait_set);
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
* do {
|
* ret = rcl_wait_set_clear_guard_conditions(&wait_set);
|
||||||
* ret = rcl_wait_set_clear_subscriptions(&wait_set);
|
|
||||||
* // ... error handling
|
|
||||||
* ret = rcl_wait_set_clear_guard_conditions(&wait_set);
|
|
||||||
* // ... error handling
|
|
||||||
* ret = rcl_wait_set_add_subscription(&wait_set, &sub1);
|
|
||||||
* // ... error handling
|
|
||||||
* ret = rcl_wait_set_add_subscription(&wait_set, &sub2);
|
|
||||||
* // ... error handling
|
|
||||||
* ret = rcl_wait_set_add_guard_condition(&wait_set, &gc1);
|
|
||||||
* // ... error handling
|
|
||||||
* ret = rcl_wait(&wait_set, RCL_MS_TO_NS(1000)); // 1000ms == 1s, passed as ns
|
|
||||||
* if (ret == RCL_RET_TIMEOUT) {
|
|
||||||
* continue;
|
|
||||||
* }
|
|
||||||
* for (int i = 0; i < wait_set.size_of_subscriptions; ++i) {
|
|
||||||
* if (wait_set.subscriptions[i]) {
|
|
||||||
* // The subscription is ready...
|
|
||||||
* }
|
|
||||||
* }
|
|
||||||
* for (int i = 0; i < wait_set.size_of_guard_conditions; ++i) {
|
|
||||||
* if (wait_set.guard_conditions[i]) {
|
|
||||||
* // The subscription is ready...
|
|
||||||
* }
|
|
||||||
* }
|
|
||||||
* } while(check_some_condition());
|
|
||||||
* // ... fini node, and subscriptions and guard conditions...
|
|
||||||
* ret = rcl_wait_set_fini(&wait_set);
|
|
||||||
* // ... error handling
|
* // ... error handling
|
||||||
|
* ret = rcl_wait_set_add_subscription(&wait_set, &sub1);
|
||||||
|
* // ... error handling
|
||||||
|
* ret = rcl_wait_set_add_subscription(&wait_set, &sub2);
|
||||||
|
* // ... error handling
|
||||||
|
* ret = rcl_wait_set_add_guard_condition(&wait_set, &gc1);
|
||||||
|
* // ... error handling
|
||||||
|
* ret = rcl_wait(&wait_set, RCL_MS_TO_NS(1000)); // 1000ms == 1s, passed as ns
|
||||||
|
* if (ret == RCL_RET_TIMEOUT) {
|
||||||
|
* continue;
|
||||||
|
* }
|
||||||
|
* for (int i = 0; i < wait_set.size_of_subscriptions; ++i) {
|
||||||
|
* if (wait_set.subscriptions[i]) {
|
||||||
|
* // The subscription is ready...
|
||||||
|
* }
|
||||||
|
* }
|
||||||
|
* for (int i = 0; i < wait_set.size_of_guard_conditions; ++i) {
|
||||||
|
* if (wait_set.guard_conditions[i]) {
|
||||||
|
* // The subscription is ready...
|
||||||
|
* }
|
||||||
|
* }
|
||||||
|
* } while(check_some_condition());
|
||||||
|
* // ... fini node, and subscriptions and guard conditions...
|
||||||
|
* ret = rcl_wait_set_fini(&wait_set);
|
||||||
|
* // ... error handling
|
||||||
|
* ```
|
||||||
*
|
*
|
||||||
* The wait set struct must be allocated, initialized, and should have been
|
* The wait set struct must be allocated, initialized, and should have been
|
||||||
* cleared and then filled with items, e.g. subscriptions and guard conditions.
|
* cleared and then filled with items, e.g. subscriptions and guard conditions.
|
||||||
* Passing a wait set with no wait-able items in it will fail.
|
* Passing a wait set with no wait-able items in it will fail.
|
||||||
* NULL items in the sets are ignored, e.g. it is valid to have as input:
|
* `NULL` items in the sets are ignored, e.g. it is valid to have as input:
|
||||||
* - subscriptions[0] = valid pointer
|
* - `subscriptions[0]` = valid pointer
|
||||||
* - subscriptions[1] = NULL
|
* - `subscriptions[1]` = `NULL`
|
||||||
* - subscriptions[2] = valid pointer
|
* - `subscriptions[2]` = valid pointer
|
||||||
* - size_of_subscriptions = 3
|
* - `size_of_subscriptions` = 3
|
||||||
* Passing an uninitialized (zero initialized) wait set struct will fail.
|
* Passing an uninitialized (zero initialized) wait set struct will fail.
|
||||||
* Passing a wait set struct with uninitialized memory is undefined behavior.
|
* Passing a wait set struct with uninitialized memory is undefined behavior.
|
||||||
*
|
*
|
||||||
|
@ -430,17 +483,17 @@ rcl_wait_set_resize_services(rcl_wait_set_t * wait_set, size_t size);
|
||||||
* This function is thread-safe for unique wait sets with unique contents.
|
* This function is thread-safe for unique wait sets with unique contents.
|
||||||
* This function cannot operate on the same wait set in multiple threads, and
|
* This function cannot operate on the same wait set in multiple threads, and
|
||||||
* the wait sets may not share content.
|
* the wait sets may not share content.
|
||||||
* For example, calling rcl_wait in two threads on two different wait sets that
|
* For example, calling rcl_wait() in two threads on two different wait sets
|
||||||
* both contain a single, shared guard condition is undefined behavior.
|
* that both contain a single, shared guard condition is undefined behavior.
|
||||||
*
|
*
|
||||||
* \param[inout] wait_set the set of things to be waited on and to be pruned if not ready
|
* \param[inout] wait_set the set of things to be waited on and to be pruned if not ready
|
||||||
* \param[in] timeout the duration to wait for the wait set to be ready, in nanoseconds
|
* \param[in] timeout the duration to wait for the wait set to be ready, in nanoseconds
|
||||||
* \return RCL_RET_OK something in the wait set became ready, or
|
* \return `RCL_RET_OK` something in the wait set became ready, or
|
||||||
* RCL_RET_INVALID_ARGUMENT if any arguments are invalid, or
|
* \return `RCL_RET_INVALID_ARGUMENT` if any arguments are invalid, or
|
||||||
* RCL_RET_WAIT_SET_INVALID if the wait set is zero initialized, or
|
* \return `RCL_RET_WAIT_SET_INVALID` if the wait set is zero initialized, or
|
||||||
* RCL_RET_WAIT_SET_EMPTY if the wait set contains no items, or
|
* \return `RCL_RET_WAIT_SET_EMPTY` if the wait set contains no items, or
|
||||||
* RCL_RET_TIMEOUT if the timeout expired before something was ready, or
|
* \return `RCL_RET_TIMEOUT` if the timeout expired before something was ready, or
|
||||||
* RCL_RET_ERROR an unspecified error occur.
|
* \return `RCL_RET_ERROR` an unspecified error occur.
|
||||||
*/
|
*/
|
||||||
RCL_PUBLIC
|
RCL_PUBLIC
|
||||||
RCL_WARN_UNUSED
|
RCL_WARN_UNUSED
|
||||||
|
|
|
@ -117,6 +117,7 @@ rcl_client_fini(rcl_client_t * client, rcl_node_t * node)
|
||||||
rcl_client_options_t
|
rcl_client_options_t
|
||||||
rcl_client_get_default_options()
|
rcl_client_get_default_options()
|
||||||
{
|
{
|
||||||
|
// !!! MAKE SURE THAT CHANGES TO THESE DEFAULTS ARE REFLECTED IN THE HEADER DOC STRING
|
||||||
static rcl_client_options_t default_options;
|
static rcl_client_options_t default_options;
|
||||||
// Must set the allocator and qos after because they are not a compile time constant.
|
// Must set the allocator and qos after because they are not a compile time constant.
|
||||||
default_options.qos = rmw_qos_profile_services_default;
|
default_options.qos = rmw_qos_profile_services_default;
|
||||||
|
|
|
@ -127,6 +127,7 @@ rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition)
|
||||||
rcl_guard_condition_options_t
|
rcl_guard_condition_options_t
|
||||||
rcl_guard_condition_get_default_options()
|
rcl_guard_condition_get_default_options()
|
||||||
{
|
{
|
||||||
|
// !!! MAKE SURE THAT CHANGES TO THESE DEFAULTS ARE REFLECTED IN THE HEADER DOC STRING
|
||||||
static rcl_guard_condition_options_t default_options;
|
static rcl_guard_condition_options_t default_options;
|
||||||
default_options.allocator = rcl_get_default_allocator();
|
default_options.allocator = rcl_get_default_allocator();
|
||||||
return default_options;
|
return default_options;
|
||||||
|
|
|
@ -197,6 +197,7 @@ rcl_node_is_valid(const rcl_node_t * node)
|
||||||
rcl_node_options_t
|
rcl_node_options_t
|
||||||
rcl_node_get_default_options()
|
rcl_node_get_default_options()
|
||||||
{
|
{
|
||||||
|
// !!! MAKE SURE THAT CHANGES TO THESE DEFAULTS ARE REFLECTED IN THE HEADER DOC STRING
|
||||||
static rcl_node_options_t default_options = {
|
static rcl_node_options_t default_options = {
|
||||||
.domain_id = RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID,
|
.domain_id = RCL_NODE_OPTIONS_DEFAULT_DOMAIN_ID,
|
||||||
};
|
};
|
||||||
|
|
|
@ -113,6 +113,7 @@ rcl_publisher_fini(rcl_publisher_t * publisher, rcl_node_t * node)
|
||||||
rcl_publisher_options_t
|
rcl_publisher_options_t
|
||||||
rcl_publisher_get_default_options()
|
rcl_publisher_get_default_options()
|
||||||
{
|
{
|
||||||
|
// !!! MAKE SURE THAT CHANGES TO THESE DEFAULTS ARE REFLECTED IN THE HEADER DOC STRING
|
||||||
static rcl_publisher_options_t default_options;
|
static rcl_publisher_options_t default_options;
|
||||||
// Must set the allocator and qos after because they are not a compile time constant.
|
// Must set the allocator and qos after because they are not a compile time constant.
|
||||||
default_options.qos = rmw_qos_profile_default;
|
default_options.qos = rmw_qos_profile_default;
|
||||||
|
|
|
@ -119,6 +119,7 @@ rcl_service_fini(rcl_service_t * service, rcl_node_t * node)
|
||||||
rcl_service_options_t
|
rcl_service_options_t
|
||||||
rcl_service_get_default_options()
|
rcl_service_get_default_options()
|
||||||
{
|
{
|
||||||
|
// !!! MAKE SURE THAT CHANGES TO THESE DEFAULTS ARE REFLECTED IN THE HEADER DOC STRING
|
||||||
static rcl_service_options_t default_options;
|
static rcl_service_options_t default_options;
|
||||||
// Must set the allocator and qos after because they are not a compile time constant.
|
// Must set the allocator and qos after because they are not a compile time constant.
|
||||||
default_options.qos = rmw_qos_profile_services_default;
|
default_options.qos = rmw_qos_profile_services_default;
|
||||||
|
|
|
@ -108,6 +108,7 @@ rcl_subscription_fini(rcl_subscription_t * subscription, rcl_node_t * node)
|
||||||
rcl_subscription_options_t
|
rcl_subscription_options_t
|
||||||
rcl_subscription_get_default_options()
|
rcl_subscription_get_default_options()
|
||||||
{
|
{
|
||||||
|
// !!! MAKE SURE THAT CHANGES TO THESE DEFAULTS ARE REFLECTED IN THE HEADER DOC STRING
|
||||||
static rcl_subscription_options_t default_options = {
|
static rcl_subscription_options_t default_options = {
|
||||||
.ignore_local_publications = false,
|
.ignore_local_publications = false,
|
||||||
};
|
};
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue