Guard conditions: remove node from constructor, fix header
* Use specific name for subscription topic * Remove references to node in the guard condition API, it's not needed * Provide implementation of guard_condition_trigger with the correct name * Change to trigger_guard_condition * remove fixed guard conditions
This commit is contained in:
parent
e40323205e
commit
087315b4c6
5 changed files with 18 additions and 42 deletions
|
@ -20,8 +20,9 @@ extern "C"
|
|||
{
|
||||
#endif
|
||||
|
||||
#include "rcl/allocator.h"
|
||||
#include "rcl/macros.h"
|
||||
#include "rcl/node.h"
|
||||
#include "rcl/types.h"
|
||||
#include "rcl/visibility_control.h"
|
||||
|
||||
/// Internal rcl guard condition implementation struct.
|
||||
|
@ -50,34 +51,24 @@ rcl_get_zero_initialized_guard_condition(void);
|
|||
/* 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().
|
||||
*
|
||||
* 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();
|
||||
* ret = rcl_guard_condition_init(
|
||||
* &guard_condition, &node, rcl_guard_condition_get_default_options());
|
||||
* &guard_condition, rcl_guard_condition_get_default_options());
|
||||
* // ... error handling, and on shutdown do deinitialization:
|
||||
* ret = rcl_guard_condition_fini(&guard_condition, &node);
|
||||
* ret = rcl_guard_condition_fini(&guard_condition);
|
||||
* // ... error handling for rcl_guard_condition_fini()
|
||||
* ret = rcl_node_fini(&node);
|
||||
* // ... error handling for rcl_node_fini()
|
||||
*
|
||||
* This function does allocate heap memory.
|
||||
* This function is not thread-safe.
|
||||
* This function is lock-free.
|
||||
*
|
||||
* \TODO(wjwwood): does this function need a node to be passed to it? (same for fini)
|
||||
*
|
||||
* \param[inout] guard_condition preallocated guard_condition structure
|
||||
* \param[in] node valid rcl node handle
|
||||
* \param[in] options the guard_condition's options
|
||||
* \return RCL_RET_OK if guard_condition was initialized successfully, or
|
||||
* RCL_RET_ALREADY_INIT if the guard condition is already initialized, or
|
||||
|
@ -90,20 +81,17 @@ RCL_WARN_UNUSED
|
|||
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);
|
||||
|
||||
/// Finalize a rcl_guard_condition_t.
|
||||
/* After calling, calls to rcl_guard_condition_trigger() will fail when using
|
||||
/* 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 does free heap memory and can allocate memory on errors.
|
||||
* This function is not thread-safe with rcl_guard_condition_trigger().
|
||||
* This function is not thread-safe with rcl_trigger_guard_condition().
|
||||
* This function is lock-free.
|
||||
*
|
||||
* \param[inout] guard_condition handle to the guard_condition to be finalized
|
||||
* \param[in] node handle to the node used to create the guard_condition
|
||||
* \return RCL_RET_OK if guard_condition was finalized successfully, or
|
||||
* RCL_RET_INVALID_ARGUMENT if any arugments are invalid, or
|
||||
* RCL_RET_ERROR if an unspecified error occurs.
|
||||
|
@ -111,7 +99,7 @@ rcl_guard_condition_init(
|
|||
RCL_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
rcl_ret_t
|
||||
rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition, rcl_node_t * node);
|
||||
rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition);
|
||||
|
||||
/// Return the default options in a rcl_guard_condition_options_t struct.
|
||||
/* This function does not allocate heap memory.
|
||||
|
@ -143,7 +131,7 @@ rcl_guard_condition_get_default_options(void);
|
|||
RCL_PUBLIC
|
||||
RCL_WARN_UNUSED
|
||||
rcl_ret_t
|
||||
rcl_guard_condition_trigger(const rcl_guard_condition_t * guard_condition);
|
||||
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.
|
||||
|
|
|
@ -87,8 +87,6 @@ rcl_get_zero_initialized_wait_set(void);
|
|||
* ret = rcl_wait_set_fini(&wait_set);
|
||||
* // ... error handling
|
||||
*
|
||||
* \TODO(wjwwood): consider the "fixed guard conditions", a la rmw's wait set.
|
||||
*
|
||||
* 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.
|
||||
|
@ -164,6 +162,9 @@ rcl_wait_set_get_allocator(const rcl_wait_set_t * wait_set, rcl_allocator_t * al
|
|||
/* This function does not guarantee that the subscription is not already in the
|
||||
* wait set.
|
||||
*
|
||||
* Also add the rmw representation to the underlying rmw array and increment
|
||||
* the rmw array count.
|
||||
*
|
||||
* This function is not thread-safe.
|
||||
* This function is lock-free.
|
||||
*
|
||||
|
@ -185,6 +186,8 @@ rcl_wait_set_add_subscription(
|
|||
/// Remove (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.
|
||||
* Sets all of the entries in the underlying rmw array to null, and sets the
|
||||
* count in the rmw array to 0.
|
||||
*
|
||||
* Calling this on an uninitialized (zero initialized) wait set will fail.
|
||||
*
|
||||
|
@ -213,6 +216,8 @@ rcl_wait_set_clear_subscriptions(rcl_wait_set_t * wait_set);
|
|||
*
|
||||
* After calling this function all values in the set will be set to NULL,
|
||||
* effectively the same as calling rcl_wait_set_clear_subscriptions().
|
||||
* Similarly, the underlying rmw representation is reallocated and reset:
|
||||
* 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.
|
||||
*
|
||||
|
|
|
@ -39,22 +39,15 @@ rcl_get_zero_initialized_guard_condition()
|
|||
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)
|
||||
{
|
||||
// Perform argument validation.
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(guard_condition, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
|
||||
const rcl_allocator_t * allocator = &options.allocator;
|
||||
RCL_CHECK_FOR_NULL_WITH_MSG(
|
||||
allocator->allocate, "allocate not set", return RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_FOR_NULL_WITH_MSG(
|
||||
allocator->deallocate, "deallocate not set", return RCL_RET_INVALID_ARGUMENT);
|
||||
// Ensure the node is valid.
|
||||
if (!node->impl || rcl_node_get_rcl_instance_id(node) != rcl_get_instance_id()) {
|
||||
RCL_SET_ERROR_MSG("node handle is invalid");
|
||||
return RCL_RET_NODE_INVALID;
|
||||
}
|
||||
// Ensure the guard_condition handle is zero initialized.
|
||||
if (guard_condition->impl) {
|
||||
RCL_SET_ERROR_MSG("guard_condition already initialized, or memory was unintialized");
|
||||
|
@ -81,16 +74,10 @@ rcl_guard_condition_init(
|
|||
}
|
||||
|
||||
rcl_ret_t
|
||||
rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition, rcl_node_t * node)
|
||||
rcl_guard_condition_fini(rcl_guard_condition_t * guard_condition)
|
||||
{
|
||||
// Perform argument validation.
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(guard_condition, RCL_RET_INVALID_ARGUMENT);
|
||||
RCL_CHECK_ARGUMENT_FOR_NULL(node, RCL_RET_INVALID_ARGUMENT);
|
||||
// Ensure the node is valid.
|
||||
if (!node->impl || rcl_node_get_rcl_instance_id(node) != rcl_get_instance_id()) {
|
||||
RCL_SET_ERROR_MSG("node handle is invalid");
|
||||
return RCL_RET_NODE_INVALID;
|
||||
}
|
||||
rcl_ret_t result = RCL_RET_OK;
|
||||
if (guard_condition->impl) {
|
||||
if (guard_condition->impl->rmw_handle) {
|
||||
|
|
|
@ -140,11 +140,7 @@ rcl_wait_set_init(
|
|||
wait_set->impl->rmw_services.services = NULL;
|
||||
wait_set->impl->rmw_services.service_count = 0;
|
||||
|
||||
static rmw_guard_conditions_t fixed_guard_conditions;
|
||||
fixed_guard_conditions.guard_conditions = NULL;
|
||||
fixed_guard_conditions.guard_condition_count = 0;
|
||||
wait_set->impl->rmw_waitset = rmw_create_waitset(
|
||||
&fixed_guard_conditions,
|
||||
2 * number_of_subscriptions + number_of_guard_conditions + number_of_clients +
|
||||
number_of_services);
|
||||
if (!wait_set->impl->rmw_waitset) {
|
||||
|
|
|
@ -129,7 +129,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
|
|||
// Process : test_subscription__rmw_opensplice_cpp <23524>
|
||||
// Thread : main thread 7fff7342d000
|
||||
// Internals : V6.4.140407OSS///v_topicNew/v_topic.c/448/21/1455157023.781423000
|
||||
const char * topic = "chatter_int64";
|
||||
const char * topic = "rcl_test_subscription_nominal_chatter_int64";
|
||||
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
||||
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options);
|
||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||
|
@ -183,7 +183,7 @@ TEST_F(CLASSNAME(TestSubscriptionFixture, RMW_IMPLEMENTATION), test_subscription
|
|||
rcl_ret_t ret;
|
||||
rcl_publisher_t publisher = rcl_get_zero_initialized_publisher();
|
||||
const rosidl_message_type_support_t * ts = ROSIDL_GET_TYPE_SUPPORT(std_msgs, msg, String);
|
||||
const char * topic = "rcl_test_subscription_chatter";
|
||||
const char * topic = "rcl_test_subscription_nominal_string_chatter";
|
||||
rcl_publisher_options_t publisher_options = rcl_publisher_get_default_options();
|
||||
ret = rcl_publisher_init(&publisher, this->node_ptr, ts, topic, &publisher_options);
|
||||
ASSERT_EQ(RCL_RET_OK, ret) << rcl_get_error_string_safe();
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue