new rcl headers for init, node, pub/sub, gc, wait

This commit is contained in:
William Woodall 2015-11-23 19:15:50 -08:00
parent d0083b725b
commit 75fafe948a
10 changed files with 1316 additions and 162 deletions

View file

@ -0,0 +1,50 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCL__ALLOCATOR_H_
#define RCL__ALLOCATOR_H_
#if __cplusplus
extern "C"
{
#endif
#include "rcl/types.h"
/// Encapsulation of an allocator.
/* NULL for allocate implies that the system should use malloc and free. */
typedef struct rcl_allocator_t {
/// Allocate memory, given a size and state structure.
/* An error should be indicated by returning null. */
void * (*allocate)(size_t size, void * state);
/// Deallocate previously allocated memory, mimicking free().
void (*deallocate)(void * pointer, void * state);
/// Reallocates if possible, otherwise it deallocates and allocates.
/* If unsupported then do deallocate and then allocate. */
void * (*reallocate)(void * pointer, size_t size, void * state);
/// Implementation defined state storage.
/* This is passed as the second parameter to the (de)allocate functions. */
void * state;
} rcl_allocator_t;
/// Return a properly initialized rcl_allocator_t with default values.
/* This function does not allocate memory. */
rcl_allocator_t
rcl_get_default_allocator();
#if __cplusplus
}
#endif
#endif // RCL__ALLOCATOR_H_

View file

@ -0,0 +1,38 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCL__ERROR_HANDLING_H_
#define RCL__ERROR_HANDLING_H_
#include "rmw/error_handling.h"
/* The error handling in RCL is just an alias to the error handling in RMW. */
typedef rmw_error_state_t rcl_error_state_t;
#define rcl_set_error_state rmw_set_error_state
#define RCL_SET_ERROR_MSG(msg) RMW_SET_ERROR_MSG(msg)
#define rcl_error_is_set rmw_error_is_set
#define rcl_get_error_state rmw_get_error_state
#define rcl_get_error_string rmw_get_error_string
#define rcl_get_error_string_safe rmw_get_error_string_safe
#define rcl_reset_error rmw_reset_error
#endif // RCL__ERROR_HANDLING_H_

View file

@ -0,0 +1,140 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCL__GUARD_CONDITION_H_
#define RCL__GUARD_CONDITION_H_
#if __cplusplus
extern "C"
{
#endif
#include "rcl/node.h"
/// Internal rcl guard condition implementation struct.
struct rcl_guard_condition_impl_t;
/// Handle for a rcl guard condition.
typedef struct rcl_guard_condition_t {
struct rcl_guard_condition_impl_t * impl;
} rcl_guard_condition_t;
/// Options available for a rcl guard condition.
typedef struct rcl_guard_condition_options_t {
/// Custom allocator for the guard condition, used for incidental allocations.
/* For default behavior (malloc/free), use: rcl_get_default_allocator() */
rcl_allocator_t allocator;
} rcl_guard_condition_options_t;
/// Return a rcl_guard_condition_t struct with members set to NULL.
/* Should be called to get a null rcl_guard_condition_t before passing to
* rcl_initalize_guard_condition().
* It's also possible to use calloc() instead of this if the rcl guard condition is
* being allocated on the heap.
*/
rcl_guard_condition_t
rcl_get_zero_initialized_guard_condition();
/// Initialize a rcl guard_condition.
/* After calling this function on a rcl_guard_condition_t, it can be passed to
* rcl_wait and can be triggered to wake rcl_wait up.
*
* The given rcl_node_t must be valid and the resulting rcl_guard_condition_t
* is only valid as long as the given rcl_node_t remains valid.
*
* Expected usage:
*
* #include <rcl/rcl.h>
*
* rcl_node_t node = rcl_get_zero_initialized_node();
* rcl_node_options_t node_ops = rcl_node_get_default_options();
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
* // ... error handling
* rcl_guard_condition_t guard_condition = rcl_get_zero_initialized_guard_condition();
* rcl_guard_condition_options_t guard_condition_ops = rcl_guard_condition_get_default_options();
* ret = rcl_guard_condition_init(&guard_condition, &node, ts, "chatter", &guard_condition_ops);
* // ... error handling, and on shutdown do deinitialization:
* ret = rcl_guard_condition_fini(&guard_condition, &node);
* // ... error handling for rcl_guard_condition_fini()
* ret = rcl_node_fini(&node);
* // ... error handling for rcl_deinitialize_node()
*
* This function is not thread-safe.
*
* \param[inout] guard_condition preallocated guard_condition structure
* \param[in] node valid rcl node handle
* \param[in] options the guard_condition's options
* \return RMW_RET_OK if guard_condition was initialized successfully, otherwise RMW_RET_ERROR
*/
rcl_ret_t
rcl_guard_condition_init(
rcl_guard_condition_t * guard_condition,
const rcl_node_t * node,
const rcl_guard_condition_options_t * options);
/// Deinitialize a rcl_guard_condition_t.
/* After calling, calls to rcl_trigger_guard_condition will fail when using
* this guard condition.
* However, the given node handle is still valid.
*
* This function is not thread-safe.
*
* \param[inout] guard_condition handle to the guard_condition to be deinitialized
* \param[in] node handle to the node used to create the guard_condition
* \return RMW_RET_OK if guard_condition was deinitialized successfully, otherwise RMW_RET_ERROR
*/
rcl_ret_t
rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition, rcl_node_t * node);
/// Return the default guard_condition options in a rcl_guard_condition_options_t.
rcl_guard_condition_options_t
rcl_guard_condition_get_default_options();
/// Trigger a rcl guard condition.
/* 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)
*
* A guard condition can be triggered from any thread.
*
* This function is thread-safe with itself, but cannot be called concurrently
* with rcl_guard_condition_fini() on the same guard condition.
*
* \param[in] guard_condition handle to the guard_condition to be triggered
* \return RMW_RET_OK if the message was published, otherwise RMW_RET_ERROR
*/
rcl_ret_t
rcl_trigger_guard_condition(const rcl_guard_condition_t * guard_condition);
/// 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:
* - guard_condition is NULL
* - guard_condition is invalid (never called init, called fini, or invalid node)
*
* The returned handle is only valid as long as the given guard_condition is valid.
*
* \TODO(wjwwood) should the return value of this be const?
*
* \param[in] guard_condition pointer to the rcl guard_condition
* \return rmw guard_condition handle if successful, otherwise NULL
*/
rmw_guard_condition_t *
rcl_guard_condition_get_rmw_guard_condition_handle(rcl_guard_condition_t * guard_condition);
#if __cplusplus
}
#endif
#endif // RCL__GUARD_CONDITION_H_

168
rcl/include/rcl/node.h Normal file
View file

@ -0,0 +1,168 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCL__NODE_H_
#define RCL__NODE_H_
#if __cplusplus
extern "C"
{
#endif
#include "rcl/allocator.h"
#include "rcl/types.h"
struct rcl_node_impl_t;
/// Handle for a ROS node.
/* This handle can be in one a few stats, which are referred to below:
* - uninitialized: memory allocated, but not initialized to anything
* - invalid: memory allocated but not usable
* - either zero initialized or shutdown (rcl_shutdown() or rcl_node_fini())
* - valid: memory allocated and usable
*/
typedef struct rcl_node_t {
/// Private implementation pointer.
struct rcl_node_impl_t * impl;
} rcl_node_t;
typedef struct rcl_node_options_t {
// bool anonymous_name;
// rmw_qos_profile_t parameter_qos;
/// If true, no parameter infrastructure will be setup.
bool no_parameters;
/// Custom allocator used for incidental allocations, e.g. node name string.
rcl_allocator_t allocator;
} rcl_node_options_t;
/// Return a rcl_node_t struct with members initialized to NULL.
/* Should be called to get rcl_node_t before passing to rcl_node_init().
* It's also possible to use calloc() instead of this if the rcl_node is being
* allocated on the heap.
*/
rcl_node_t
rcl_get_zero_initialized_node();
/// Initialize a ROS node.
/* 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.
*
* After calling the ROS node object can be used to create other middleware
* primitives like publishers, services, parameters, and etc.
*
* 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.
*
* A node contains infrastructure for ROS parameters, which include advertising
* publishers and service servers.
* So this function will create those external parameter interfaces even if
* parameters are not used later.
*
* This function should be called on a rcl_node_t exactly once, and calling it
* multiple times is undefined behavior.
*
* Expected usage:
*
* rcl_node_t node = rcl_get_zero_initialized_node();
* rcl_node_options_t * node_ops = rcl_node_get_default_options();
* rcl_ret_t ret = rcl_node_init(&node, "node_name", node_ops);
* // ... error handling and then use the node, but finally deinitialize it:
* ret = rcl_node_fini(&node);
* // ... error handling for rcl_node_fini()
*
* This function is not thread-safe.
*
* \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
*
* \param[inout] node a preallocated node structure
* \param[in] name the name of the node
* \param[in] options the node options; pass null to use default options
* \return RMW_RET_OK if node was initialized successfully, otherwise RMW_RET_ERROR
*/
rcl_ret_t
rcl_node_init(rcl_node_t * node, const char * name, const rcl_node_options_t * options);
/// Deinitialize a rcl_node_t.
/* Shuts down any automatically created infrastructure and deallocates memory.
* After calling, the rcl_node_t can be safely released.
*
* Any middleware primitives created by the user, e.g. publishers, services, etc.,
* are invalid after deinitialization.
*
* This function is not thread-safe.
*
* \param[in] node handle to the node to be deinitialized
* \return RMW_RET_OK if node was deinitialized successfully, otherwise RMW_RET_ERROR
*/
rcl_ret_t
rcl_node_fini(rcl_node_t * node);
/// Return the default node options in a rcl_node_options_t.
rcl_node_options_t
rcl_node_get_default_options();
/// Get the name of the node.
/* This function returns the node's internal name string.
* This function can fail, and therefore return NULL, if:
* - node is NULL
* - 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 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.
*
* \param[in] node pointer to the node
* \return name string if successful, otherwise NULL
*/
const char *
rcl_node_get_name(const rcl_node_t * node);
/// Return the rcl node options.
/* This function returns the node's internal options struct.
* This function can fail, and therefore return NULL, if:
* - node is NULL
* - 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 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.
*
* \param[in] node pointer to the node
* \return options struct if successful, otherwise NULL
*/
const rcl_node_options_t *
rcl_node_get_options(const rcl_node_t * node);
/// 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:
* - node is NULL
* - node has not been initialized (the implementation is invalid)
*
* The returned handle is only valid as long as the given node is valid.
*
* \TODO(wjwwood) should the return value of this be const?
*
* \param[in] node pointer to the rcl node
* \return rmw node handle if successful, otherwise NULL
*/
rmw_node_t *
rcl_node_get_rmw_node_handle(const rcl_node_t * node);
#if __cplusplus
}
#endif
#endif // RCL__NODE_H_

267
rcl/include/rcl/publisher.h Normal file
View file

@ -0,0 +1,267 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCL__PUBLISHER_H_
#define RCL__PUBLISHER_H_
#if __cplusplus
extern "C"
{
#endif
#include "rosidl_generator_c/message_type_support.h"
#include "rcl/node.h"
/// Internal rcl publisher implementation struct.
struct rcl_publisher_impl_t;
/// Handle for a rcl publisher.
typedef struct rcl_publisher_t {
struct rcl_publisher_impl_t * impl;
} rcl_publisher_t;
/// Options available for a rcl publisher.
typedef struct rcl_publisher_options_t {
/// Middleware quality of service settings for the publisher.
rmw_qos_profile_t qos;
/// Custom allocator for the publisher, used for incidental allocations.
/* For default behavior (malloc/free), use: rcl_get_default_allocator() */
rcl_allocator_t allocator;
} rcl_publisher_options_t;
/// 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().
* It's also possible to use calloc() instead of this if the rcl_publisher is
* being allocated on the heap.
*/
rcl_publisher_t
rcl_get_zero_initialized_publisher();
/// Initialize a rcl publisher.
/* 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().
*
* The given rcl_node_t must be valid and the resulting rcl_publisher_t is only
* valid as long as the given rcl_node_t remains valid.
*
* The rosidl_message_type_support_t is obtained on a per .msg type basis.
* When the user defines a ROS message, code is generated which provides the
* required rosidl_message_type_support_t object.
* This object can be obtained using a language appropriate mechanism.
* \TODO(wjwwood) probably should talk about this once and link to it instead
* For C this macro can be used (using std_msgs/String as an example):
*
* #include <rosidl_generator_c/message_type_support.h>
* #include <std_msgs/msgs/string.h>
* rosidl_message_type_support_t * string_ts =
* ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
*
* For C++ a template function is used:
*
* #include <rosidl_generator_cpp/message_type_support.hpp>
* #include <std_msgs/msgs/string.hpp>
* 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
* information used to publish messages.
*
* \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
* format.
*
* The options struct allows the user to set the quality of service settings as
* well as a custom allocator which is used when (de)initializing the publisher
* to allocate space for incidental things, e.g. the topic name string.
*
* Expected usage (for C messages):
*
* #include <rcl/rcl.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_options_t node_ops = rcl_node_get_default_options();
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
* // ... error handling
* 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_options_t publisher_ops = rcl_publisher_get_default_options();
* ret = rcl_publisher_init(&publisher, &node, ts, "chatter", &publisher_ops);
* // ... error handling, and on shutdown do deinitialization:
* ret = rcl_publisher_fini(&publisher, &node);
* // ... error handling for rcl_publisher_fini()
* ret = rcl_node_fini(&node);
* // ... error handling for rcl_deinitialize_node()
*
* This function is not thread-safe.
*
* \param[inout] publisher preallocated publisher structure
* \param[in] node valid rcl node handle
* \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] options publisher options, including quality of service settings
* \return RMW_RET_OK if publisher was initialized successfully, otherwise RMW_RET_ERROR
*/
rcl_ret_t
rcl_publisher_init(
rcl_publisher_t * publisher,
const rcl_node_t * node,
const rosidl_message_type_support_t * type_support,
const char * topic_name,
const rcl_publisher_options_t * options);
/// Deinitialize a rcl_publisher_t.
/* 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).
*
* After calling, calls to rcl_publish will fail when using this publisher.
* However, the given node handle is still valid.
*
* This function is not thread-safe.
*
* \param[inout] publisher handle to the publisher to be deinitialized
* \param[in] node handle to the node used to create the publisher
* \return RMW_RET_OK if publisher was deinitialized successfully, otherwise RMW_RET_ERROR
*/
rcl_ret_t
rcl_publisher_fini(rcl_publisher_t * publisher, rcl_node_t * node);
/// Return the default publisher options in a rcl_publisher_options_t.
rcl_publisher_options_t
rcl_publisher_get_default_options();
// TODO(wjwwood): I have an idea on how to do a type-checking macro version of
// publish using C11's _Generic "generic selection", but it
// needs support from the generated code (look into it later)
// It might also use static assert, see:
// http://www.robertgamble.net/2012/01/c11-static-assertions.html
// #define RCL_PUBLISH(publisher, ros_message) ...
/// 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
* parameter and the type associate with the publisher (via the type support)
* match.
* Passing a different type to publish produces undefined behavior and cannot
* be checked by this function and therefore no deliberate error will occur.
*
* TODO(wjwwood): update after researching what the blocking behavior is
* or optionally link to a document that describes blocking
* behavior is more detail.
* 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,
* serializing the message, collecting publish statistics, etc.
* The last thing it will do is call the underlying middleware's publish
* function which may or may not block based on the quality of service settings
* given via the publisher options in rcl_publisher_init().
* For example, if the reliability is set to reliable, then a publish may block
* until space in the publish queue is available, but if the reliability is set
* to best effort then it should not block.
*
* The ROS message given by the ros_message void pointer is always owned by the
* calling code, but should remain constant during publish.
*
* This function is thread safe so long as access to both the publisher and the
* ros_message is synchronized.
* 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
* is not, e.g. calling rcl_publish and rcl_publisher_fini concurrently
* is not allowed.
* Before calling rcl_publish the message can change and after calling
* rcl_publish the message can change, but it cannot be changed during the
* publish call.
* The same ros_message, however, can be passed to multiple calls of
* rcl_publish simultaneously, even if the publishers differ.
* The ros_message is unmodified by rcl_publish.
*
* \param[in] publisher handle to the publisher which will do the publishing
* \param[in] ros_message type-erased pointer to the ROS message
* \return RMW_RET_OK if the message was published, otherwise RMW_RET_ERROR
*/
rcl_ret_t
rcl_publish(const rcl_publisher_t * publisher, const void * ros_message);
/// 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:
* - publisher is NULL
* - 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 value of the string may change if the topic name changes, and therefore
* copying the string is recommended if this is a concern.
*
* This function is not thread-safe, and copying the result is not thread-safe.
* \TODO(wjwwood): should we provide a thread-safe copy_topic_name?
*
* \param[in] publisher pointer to the publisher
* \return name string if successful, otherwise NULL
*/
const char *
rcl_publisher_get_topic_name(const rcl_publisher_t * publisher);
/// Return the rcl publisher options.
/* This function returns the publisher's internal options struct.
* This function can fail, and therefore return NULL, if the:
* - publisher is NULL
* - 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 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.
*
* This function is not thread-safe, and copying the result is not thread-safe.
* \TODO(wjwwood): should we provide a thread-safe copy_publisher_options?
*
* \param[in] publisher pointer to the publisher
* \return options struct if successful, otherwise NULL
*/
const rcl_publisher_options_t *
rcl_publisher_get_options(rcl_publisher_t * publisher);
/// 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:
* - publisher is NULL
* - publisher is invalid (never called init, called fini, or invalid node)
*
* The returned handle is only valid as long as the given publisher is valid.
*
* \TODO(wjwwood) will the publisher ever need to remove and recreate the rmw
* handle under the hood? Perhaps not now, but if we add the
* ability to reconfigure, alias, or remap topics, and don't
* implement that into rmw, then we should consider the
* implications here. This argument applies to other parts of
* the interface, but I'll just mention it here.
*
* \TODO(wjwwood) should the return value of this be const?
*
* \param[in] publisher pointer to the rcl publisher
* \return rmw publisher handle if successful, otherwise NULL
*/
rmw_publisher_t *
rcl_publisher_get_rmw_publisher_handle(rcl_publisher_t * publisher);
int main() {
}
#if __cplusplus
}
#endif
#endif // RCL__PUBLISHER_H_

View file

@ -15,140 +15,71 @@
#ifndef RCL__RCL_H_
#define RCL__RCL_H_
#include <stdbool.h> // For bool
#include <stddef.h> // For size_t
#if __cplusplus
extern "C"
{
#endif
// For rosidl_message_type_support_t
#include <rosidl_generator_c/message_type_support.h>
#include "rcl/node.h"
#include "rcl/publisher.h"
#include "rcl/subscription.h"
#include "rcl/types.h"
#include "rcl/types.h" // For rcl_*_t types
/// Global initialization for rcl; should be called once per process.
/// Global initialization of rcl.
/* 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
* after each call to rcl_shutdown.
* 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
* 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
* you have to return from the callback, and therefore exit any in-progress
* call to a spin function, before calling rcl_init again.
*
* The argc and argv parameters can contain command line arguments for the
* program.
* rcl specific arguments will be parsed and removed, but other arguments will
* be ignored.
*
* \param[in] argc number of strings in argv
* \param[in] argv command line arguments; rcl specific arguments are removed
* \return RCL_RET_OK if initialization is successful, otherwise RCL_RET_ERROR
* or RCL_RET_ALREADY_INIT if rcl_init has already been called
*/
rcl_ret_t
rcl_init(int argc, char ** argv);
/// Creates a rcl_node_t; used to implement a ROS Node.
rcl_node_t *
rcl_create_node(const char * name);
/// Destroys a rcl_node_t.
/// 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 can only be called once after each call to rcl_init.
* Repeated calls will fail with RCL_RET_NOT_INIT.
* This function is not thread safe.
*
* When this function is called:
* - Any rcl objects created since the last call to rcl_init are invalidated.
* - Calls to rcl_ok will return false.
* - Any executors waiting for work (within a call to spin) are interrupted.
* - No new work (executing callbacks) will be done in executors.
* - Currently running work in executors will be finished.
*
* \return RCL_RET_OK if shutdown is successful, otherwise RCL_RET_ERROR or
* RCL_RET_NOT_INIT if rcl_init has not yet been called
*/
rcl_ret_t
rcl_destroy_node(rcl_node_t * node);
rcl_shutdown();
/// Creates a rcl_publisher_t; used to implement a ROS Publisher.
rcl_publisher_t *
rcl_create_publisher(
const rcl_node_t * node,
const rosidl_message_type_support_t * type_support,
const char * topic_name,
size_t queue_size);
/// Return true until rcl_shutdown is called, then false.
/* This function is thread safe. */
bool
rcl_ok();
/// Destroys a rcl_publisher_t.
rcl_ret_t
rcl_destroy_publisher(rcl_publisher_t * publisher);
/// Publishes a ROS message to a ROS Topic using a rcl_publisher_t.
rcl_ret_t
rcl_publish(const rcl_publisher_t * publisher, const void * ros_message);
/// Creates a rcl_subscription_t; used to implement a ROS Subscription.
rcl_subscription_t *
rcl_create_subscription(
const rcl_node_t * node,
const rosidl_message_type_support_t * type_support,
const char * topic_name,
size_t queue_size,
bool ignore_local_publications);
/// Destroys a rcl_subscription_t.
rcl_ret_t
rcl_destroy_subscription(rcl_subscription_t * subscription);
/// Takes a ROS message from a given rcl_subscription_t if one is available.
rcl_ret_t
rcl_take(const rcl_subscription_t * subscriber, void * ros_message);
/// Creates a rcl_guard_condition_t; is used by the implementation to
/// asynchronously interrupt rmw_wait.
rcl_guard_condition_t *
rcl_create_guard_condition();
/// Destroys a rcl_guard_condition_t.
rcl_ret_t
rcl_destroy_guard_condition(rcl_guard_condition_t * guard_condition);
/// Triggers the condition, which will interrupt rmw_wait asynchronously.
rcl_ret_t
rcl_trigger_guard_condition(const rcl_guard_condition_t * guard_condition);
/// Creates a rcl_callback_group_t, which provides hints about how to execute
/// groups of callbacks to an executor.
rcl_callback_group_t *
rcl_create_callback_group(rcl_node_t * node);
/// Destroys a rcl_callback_group_t.
rcl_ret_t
rcl_destroy_callback_group(rcl_callback_group_t * callback_group);
/// Creates a rcl_subscription_info_t, which associates rcl_subscription_t's
/// to a callback group.
rcl_subscription_info_t *
rcl_create_subscription_info(
rcl_subscription_t * const subscription,
rcl_callback_group_t * const callback_group);
/// Destroys a rcl_subscription_info_t.
rcl_ret_t
rcl_destroy_subscription_info(rcl_subscription_info_t * subscription_info);
/// Creates a rcl_timer_info_t, which associates a ROS Timer's guard condition
/// with a callback group.
rcl_timer_info_t *
rcl_create_timer_info(
rcl_guard_condition_t * const guard_condition,
rcl_callback_group_t * const callback_group);
/// Destroys a rcl_timer_info_t.
rcl_ret_t
rcl_destroy_timer_info(rcl_timer_info_t * timer_info);
/// Creates a rcl_executor_helper_t, which is a collection of callable items.
rcl_executor_helper_t *
rcl_create_executor_helper();
/// Destroys a rcl_executor_helper_t.
rcl_ret_t
rcl_destroy_executor_helper(rcl_executor_helper_t * executor_helper);
/// Add a rcl_subscription_info_t to the collection of callable items.
rcl_ret_t
rcl_add_subscription_info(
rcl_executor_helper_t * executor_helper,
rcl_subscription_info_t * subscription_info);
/// Removes a rcl_subscription_t from the collection of callable items.
rcl_ret_t
rcl_remove_subscription_info(
rcl_executor_helper_t * executor_helper,
rcl_subscription_info_t * subscription_info);
/// Add a rcl_timer_info_t to the collection of callable items.
rcl_ret_t
rcl_add_timer_info(
rcl_executor_helper_t * executor_helper,
rcl_timer_info_t * timer_info);
/// Removes a rcl_subscription_t from the collection of callable items.
rcl_ret_t
rcl_remove_timer_info(
rcl_executor_helper_t * executor_helper,
rcl_timer_info_t * timer_info);
/// Finds the next ready to be called item if one exists; optionally blocking.
rcl_ret_t
rcl_get_next_any_executable(
rcl_executor_helper_t * executor_helper,
rcl_any_executable_t * any_executable,
bool non_blocking);
#if __cplusplus
}
#endif
#endif // RCL__RCL_H_

View file

@ -0,0 +1,256 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCL__SUBSCRIPTION_H_
#define RCL__SUBSCRIPTION_H_
#if __cplusplus
extern "C"
{
#endif
#include "rosidl_generator_c/message_type_support.h"
#include "rcl/node.h"
/// Internal rcl implementation struct.
struct rcl_subscription_impl_t;
/// Handle for a rcl subscription.
typedef struct rcl_subscription_t {
struct rcl_subscription_impl_t * impl;
} rcl_subscription_t;
/// Options available for a rcl subscription.
typedef struct rcl_subscription_options_t {
/// Middleware quality of service settings for the subscription.
rmw_qos_profile_t qos;
/// If true, messages published from within the same node are ignored.
bool ignore_local_publications;
/// Custom allocator for the subscription, used for incidental allocations.
/* For default behavior (malloc/free), see: rcl_get_default_allocator() */
rcl_allocator_t allocator;
} rcl_subscription_options_t;
/// 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().
* It's also possible to use calloc() instead of this if the rcl_subscription_t
* is being allocated on the heap.
*/
rcl_subscription_t
rcl_get_zero_initialized_subscription();
/// Initialize a ROS subscription.
/* 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().
*
* The given rcl_node_t must be valid and the resulting rcl_subscription_t is
* only valid as long as the given rcl_node_t remains valid.
*
* The rosidl_message_type_support_t is obtained on a per .msg type basis.
* When the user defines a ROS message, code is generated which provides the
* required rosidl_message_type_support_t object.
* This object can be obtained using a language appropriate mechanism.
* \TODO(wjwwood) probably should talk about this once and link to it instead
* For C this macro can be used (using std_msgs/String as an example):
*
* #include <rosidl_generator_c/message_type_support.h>
* #include <std_msgs/msgs/string.h>
* rosidl_message_type_support_t * string_ts =
* ROSIDL_GET_MESSAGE_TYPE_SUPPORT(std_msgs, String);
*
* For C++ a template function is used:
*
* #include <rosidl_generator_cpp/message_type_support.hpp>
* #include <std_msgs/msgs/string.hpp>
* 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
* information used to publish messages.
*
* \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
* format.
*
* The options struct allows the user to set the quality of service settings as
* well as a custom allocator which is used when (de)initializing the
* subscription to allocate space for incidental things, e.g. the topic
* name string.
*
* Expected usage (for C messages):
*
* #include <rcl/rcl.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_options_t node_ops = rcl_node_get_default_options();
* rcl_ret_t ret = rcl_node_init(&node, "node_name", &node_ops);
* // ... error handling
* 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_options_t subscription_ops = rcl_subscription_get_default_options();
* ret = rcl_subscription_init(&subscription, &node, ts, "chatter", &subscription_ops);
* // ... error handling, and when finished deinitialization
* ret = rcl_subscription_fini(&subscription, &node);
* // ... error handling for rcl_subscription_fini()
* ret = rcl_node_fini(&node);
* // ... error handling for rcl_deinitialize_node()
*
* This function is not thread-safe.
*
* \param[out] subscription preallocated subscription structure
* \param[in] node valid rcl node handle
* \param[in] type_support type support object for the topic's type
* \param[in] topic_name the name of the topic
* \param[in] options subscription options, including quality of service settings
* \return RMW_RET_OK if subscription was initialized successfully, otherwise RMW_RET_ERROR
*/
rcl_ret_t
rcl_subscription_init(
rcl_subscription_t * subscription,
const rcl_node_t * node,
const rosidl_message_type_support_t * type_support,
const char * topic_name,
const rcl_subscription_options_t * options);
/// Deinitialize a rcl_subscription_t.
/* After calling, the node will no longer be subscribed on this topic
* (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
* subscription.
* Additioanlly rcl_wait will be interrupted if currently blocking.
* However, the given node handle is still valid.
*
* This function is not thread-safe.
*
* \param[inout] subscription handle to the subscription to be deinitialized
* \param[in] node handle to the node used to create the subscription
* \return RMW_RET_OK if subscription was deinitialized successfully, otherwise RMW_RET_ERROR
*/
rcl_ret_t
rcl_subscription_fini(rcl_subscription_t * subscription, rcl_node_t * node);
/// Return the default subscription options in a rcl_subscription_options_t.
rcl_subscription_options_t
rcl_subscription_get_default_options();
/// 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
* parameter and the type associate with the subscription, via the type
* support, match.
* Passing a different type to rcl_take produces undefined behavior and cannot
* be checked by this function and therefore no deliberate error will occur.
*
* TODO(wjwwood) blocking of take?
* TODO(wjwwood) pre- and post-conditions for message ownership?
* TODO(wjwwood) is rcl_take thread-safe?
*
* The ros_message pointer should point to an already allocated ROS message
* struct of the correct type, into which the taken ROS message will be copied
* if one is available.
* If taken is false after calling, then the ROS message will be unmodified.
*
* If allocation is required when taking the message, e.g. if space needs to
* be allocated for a dynamically sized array in the target message, then the
* allocator given in the subscription options is used.
*
* The taken pointer should point to an already allocated boolean in which the
* result can be stored.
*
* The rmw message_info struct contains meta information about this particular
* message instance, like what the GUID of the publisher which published it
* originally or whether or not the message received from within the same
* process.
* The message_info parameter should be an already allocated rmw_message_info_t
* structure.
* Passing NULL for message_info will be ignored.
*
* \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[out] taken pointer to a bool, if set to false a message was not taken
* \param[out] message_info rmw struct which contains meta-data for the message
* \return RMW_RET_OK if the message was published, otherwise RMW_RET_ERROR
*/
rcl_ret_t
rcl_take(
const rcl_subscription_t * subscription,
void * ros_message,
bool * taken,
rmw_message_info_t * message_info);
/// 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:
* - subscription is NULL
* - subscription is invalid (never called init, called fini, or invalid node)
*
* 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
* copying the string is recommended if this is a concern.
*
* This function is not thread-safe, and copying the result is not thread-safe.
* \TODO(wjwwood): should we provide a thread-safe copy_topic_name?
*
* \param[in] subscription the pointer to the subscription
* \return name string if successful, otherwise NULL
*/
const char *
rcl_subscription_get_topic_name(const rcl_subscription_t * subscription);
/// Return the rcl subscription options.
/* This function returns the subscription's internal options struct.
* This function can fail, and therefore return NULL, if the:
* - subscription is NULL
* - subscription is invalid (never called init, called fini, or invalid node)
*
* 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,
* 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.
* \TODO(wjwwood): should we provide a thread-safe copy_subscription_options?
*
* \param[in] subscription pointer to the subscription
* \return options struct if successful, otherwise NULL
*/
const rcl_subscription_options_t *
rcl_subscription_get_options(rcl_subscription_t * subscription);
/// 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:
* - subscription is NULL
* - subscription is invalid (never called init, called fini, or invalid node)
*
* The returned handle is only valid as long as the rcl subscription is valid.
*
* \TODO(wjwwood) should the return value of this be const?
*
* This function is not thread-safe.
*
* \param[in] subscription pointer to the rcl subscription
* \return rmw subscription handle if successful, otherwise NULL
*/
rmw_subscription_t *
rcl_subscription_get_rmw_subscription_handle(rcl_subscription_t * subscription);
#if __cplusplus
}
#endif
#endif // RCL__SUBSCRIPTION_H_

31
rcl/include/rcl/time.h Normal file
View file

@ -0,0 +1,31 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCL__TIME_H_
#define RCL__TIME_H_
#if __cplusplus
extern "C"
{
#endif
#include "rmw/rmw.h"
typedef rmw_time_t rcl_time_t;
#if __cplusplus
}
#endif
#endif // RCL__TIME_H_

View file

@ -19,40 +19,19 @@
typedef rmw_ret_t rcl_ret_t;
#define RCL_RET_OK RMW_RET_OK
typedef rmw_node_t rcl_node_t;
typedef rmw_publisher_t rcl_publisher_t;
typedef rmw_subscription_t rcl_subscription_t;
typedef rmw_guard_condition_t rcl_guard_condition_t;
typedef rmw_subscriptions_t rcl_subscriptions_t;
typedef rmw_guard_conditions_t rcl_guard_conditions_t;
typedef struct rcl_callback_group_t
{
rcl_node_t ** node;
} rcl_callback_group_t;
typedef struct rcl_subscription_info_t
{
rcl_subscription_t ** subscription;
rcl_callback_group_t ** callback_group;
} rcl_subscription_info_t;
typedef struct rcl_timer_info_t
{
rcl_guard_condition_t ** guard_condition;
rcl_callback_group_t ** callback_group;
} rcl_timer_info_t;
typedef struct rcl_executor_helper_t
{
// TODO(wjwwood): fill with something
} rcl_executor_helper_t;
typedef struct rcl_any_executable_t
{
rcl_subscription_info_t ** subscription_info;
rcl_timer_info_t ** timer_info;
} rcl_any_executable_t;
#define RCL_RET_ERROR RMW_RET_ERROR
#define RCL_RET_TIMEOUT RMW_RET_TIMEOUT
// rcl specific ret codes start at 100
#define RCL_RET_ALREADY_INIT 100
#define RCL_RET_NOT_INIT 101
// rcl node specific ret codes in 2XX
// rcl publisher specific ret codes in 3XX
// rcl subscription specific ret codes in 4XX
// rcl service client specific ret codes in 5XX
// rcl service server specific ret codes in 6XX
// rcl guard condition specific ret codes in 7XX
// rcl wait and wait set specific ret codes in 8XX
#define RCL_RET_WAIT_SET_EMPTY 800
#define RCL_RET_WAIT_SET_FULL 801
#endif // RCL__TYPES_H_

294
rcl/include/rcl/wait.h Normal file
View file

@ -0,0 +1,294 @@
// Copyright 2015 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#ifndef RCL__WAIT_H_
#define RCL__WAIT_H_
#if __cplusplus
extern "C"
{
#endif
#include <stdbool.h>
#include <stddef.h>
#include "rcl/subscription.h"
#include "rcl/guard_condition.h"
#include "rcl/time.h"
#include "rcl/types.h"
struct rcl_wait_set_impl_t;
/// Container for subscription's, guard condition's, etc to be waited on.
typedef struct rcl_wait_set_t {
/// Storage for subscription pointers.
rcl_subscription_t ** subscriptions;
size_t size_of_subscriptions;
size_t __current_subscription_offset;
/// Storage for guard condition pointers.
rcl_guard_condition_t ** guard_conditions;
size_t size_of_guard_conditions;
size_t __current_guard_condition_offset;
/// Allocator for storage.
rcl_allocator_t allocator;
/// If set to true, actions like add_subscription will fail until cleared.
bool pruned;
/// Implementation specific storage.
rcl_wait_set_impl_t * impl;
} rcl_wait_set_t;
/// Return a rcl_wait_set_t struct with members set to NULL.
rcl_wait_set_t
rcl_get_zero_initialized_wait_set();
/// Initialize a rcl wait set with space for items to be waited on.
/* This function allocates space for the subscriptions and other wait-able
* entities that can be stored in the wait set.
* It also sets the allocator to the given one and initializes the pruned
* member to be false.
*
* 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
* undefined.
* Calling this function on a wait set that has already been initialized will
* result in an error.
* A wait set can be reinitialized if rcl_wait_set_fini() was called on it.
*
* To use the default allocator use rcl_get_default_allocator().
*
* Expected usage:
*
* #include <rcl/wait.h>
*
* 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());
* // ... error handling, and then after using call matching fini:
* ret = rcl_wait_set_fini(&wait_set);
* // ... error handling
*
* This function is thread-safe for different wait_set objects.
* Thread-safety of this function requires a thread-safe allocator if the
* allocator is shared with other parts of the system.
*
* \param[inout] wait_set the wait set struct to be initialized
* \param[in] number_of_subscriptions size of the subscriptions set
* \param[in] number_of_guard_conditions size of the guard conditions set
* \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
* RCL_RET_ALREADY_INIT if the wait set is not zero initialized, or
* RCL_RET_ERROR if an unspecified error occurs.
*/
rcl_ret_t
rcl_wait_set_init(
rcl_wait_set_t * wait_set,
size_t number_of_subscriptions,
size_t number_of_guard_conditions,
rcl_allocator_t allocator);
/// Finalize a rcl wait set.
/* Deallocates any memory in the wait set that was allocated in
* rcl_wait_set_init() using the allocator given in the initialization.
*
* Calling this function on a zero initialized wait set will do nothing and
* return RCL_RET_OK.
* Calling this function on uninitialized memory results in undefined behavior.
* After calling this function the wait set will once again be zero initialized
* and so calling this function or rcl_wait_set_init() immediately after will
* succeed.
*
* This function is not thread-safe.
*
* \param[inout] wait_set the wait set struct to be finalized.
* \return RCL_RET_OK if the finalization was successful, otherwise RCL_RET_ERROR
*/
rcl_ret_t
rcl_wait_set_fini(rcl_wait_set_t * wait_set);
/// Stores a pointer to the given subscription in next empty spot in the set.
/* This function does not guarantee that the subscription is not already in the
* wait set.
*
* This function is not thread-safe.
*
* \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
* \return RCL_RET_OK if added successfully, or
* RCL_RET_WAIT_SET_FULL if the subscription set is full, or
* RCL_RET_NOT_INIT if the wait set is zero initialized, or
* RCL_RET_ERROR if an unspecified error occurs.
*/
rcl_ret_t
rcl_wait_set_add_subscription(
rcl_wait_set_t * wait_set,
const rcl_subscription_t * subscription);
/// Removes (sets to NULL) the subscriptions in the wait set.
/* This function should be used after passing using rcl_wait, but before
* adding new subscriptions to the set.
*
* Calling this on an uninitialized (zero initialized) wait set will fail.
*
* This function is not thread-safe.
*
* \param[inout] wait_set struct to have its subscriptions cleared
* \return RCL_RET_OK if cleared successfully, or
* RCL_RET_NOT_INIT if the wait set is zero initialized, or
* RCL_RET_ERROR if an unspecified error occurs.
*/
rcl_ret_t
rcl_wait_set_clear_subscriptions(rcl_wait_set_t * wait_set);
/// Reallocates space for the subscriptions in the wait set.
/* This function will deallocate and reallocate the memory for the
* subscriptions set.
*
* 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
* wait set's initialization.
*
* After calling this function all values in the set will be set to NULL,
* effectively the same as calling rcl_wait_set_clear_subscriptions().
*
* 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 function is not thread-safe.
*
* \param[inout] wait_set struct to have its subscriptions cleared
* \param[in] size a size for the new set
* \return RCL_RET_OK if resized successfully, or
* RCL_RET_ERROR if an unspecified error occurs.
*/
rcl_ret_t
rcl_wait_set_resize_subscriptions(rcl_wait_set_t * wait_set, size_t size);
/// Stores a pointer to the guard condition in next empty spot in the set.
/* This function behaves exactly the same as for subscriptions.
* \see rcl_wait_set_add_subscription
*/
rcl_ret_t
rcl_wait_set_add_guard_condition(
rcl_wait_set_t * wait_set,
const rcl_guard_condition_t * guard_condition);
/// Removes (sets to NULL) the guard conditions in the wait set.
/* This function behaves exactly the same as for subscriptions.
* \see rcl_wait_set_clear_subscriptions
*/
rcl_ret_t
rcl_wait_set_clear_guard_conditions(rcl_wait_set_t * wait_set);
/// Reallocates space for the subscriptions in the wait set.
/* This function behaves exactly the same as for subscriptions.
* \see rcl_wait_set_resize_subscriptions
*/
rcl_ret_t
rcl_wait_set_resize_guard_conditions(rcl_wait_set_t * wait_set, size_t size);
/// 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
* to the underlying rmw_wait function.
*
* The items in the wait set will be either left untouched or set to NULL after
* this function returns.
* Items that are not NULL are ready, where ready means different things based
* on the type of the item.
* For subscriptions this means there are messages that can be taken.
* For guard conditions this means the guard condition was triggered.
*
* Expected usage:
*
* #include <rcl/rcl.h>
*
* // rcl_init() called successfully before here...
* rcl_node_t node; // initialize this, see rcl_node_init()
* rcl_subscription_t sub1; // 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_wait_set_t wait_set = rcl_get_zero_initialized_wait_set();
* rcl_ret_t ret = rcl_wait_set_init(&wait_set, 2, 1, rcl_get_default_allocator());
* // ... error handling
* do {
* 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
* rcl_time_t timeout = {1, 0}; // 1 second and 0 nanoseconds.
* ret = rcl_wait(&wait_set, &timeout);
* 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
* 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.
* NULL items in the sets are ignored, e.g. it is valid to have as input:
* - subscriptions[0] = valid pointer
* - subscriptions[1] = NULL
* - subscriptions[2] = valid pointer
* - size_of_subscriptions = 3
* Passing an uninitialized (zero initialized) wait set struct will fail.
* Passing a wait set struct with uninitialized memory is undefined behavior.
*
* If the timeout pointer is NULL then this function will block indefinitely
* until something in the wait set is valid or it is interrupted.
* If the timeout contains 0 for seconds and nanoseconds this function will be
* non-blocking; checking what's ready but not waiting if nothing is ready yet.
* If the timeout contains a non-zero time then this function will return after
* that period of time has elapsed if something in the wait set does not become
* ready before then.
* The timeout's value is not changed.
* Passing a timeout struct with uninitialized memory is undefined behavior.
*
* This function is not thread-safe and cannot be called concurrently, even if
* the given wait sets are not the same and non-overlapping in contents.
*
* \param[inout] wait_set the set of things to be waited on and to be pruned if not ready
* \param[in] timeout the time duration to wait something in the wait set to be ready
* \return RCL_RET_OK something in the wait set became ready, or
* RCL_RET_TIMEOUT timeout expired before something was ready, or
* RCL_RET_NOT_INIT wait set is zero initialized, or
* RCL_RET_WAIT_SET_EMPTY wait set contains no items, or
* RCL_RET_ERROR an unspecified error occur.
*/
rcl_ret_t
rcl_wait(rcl_wait_set_t * wait_set, const rcl_time_t * timeout);
#if __cplusplus
}
#endif
#endif // RCL__WAIT_H_