Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

export internal subscriptions of feedback and status #3

Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
10 changes: 10 additions & 0 deletions rcl/CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,16 @@
Changelog for package rcl
^^^^^^^^^^^^^^^^^^^^^^^^^

3.0.0 (2021-03-23)
------------------

2.6.0 (2021-03-18)
------------------
* Add support for rmw_connextdds (`#895 <https://github.com/ros2/rcl/issues/895>`_)
* Put an argument list of 'void' where no arguments are expected. (`#899 <https://github.com/ros2/rcl/issues/899>`_)
* Cleanup documentation for doxygen. (`#896 <https://github.com/ros2/rcl/issues/896>`_)
* Contributors: Andrea Sorbini, Chris Lalancette

2.5.2 (2021-02-05)
------------------
* Reference test resources directly from source tree (`#554 <https://github.com/ros2/rcl/issues/554>`_)
Expand Down
31 changes: 31 additions & 0 deletions rcl/include/rcl/macros.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,37 @@ extern "C"

#define RCL_UNUSED(x) RCUTILS_UNUSED(x)

#define RCL_RET_FROM_RCUTIL_RET(rcl_ret_var, rcutils_expr) \
{ \
rcutils_ret_t rcutils_ret = rcutils_expr; \
if (RCUTILS_RET_OK != rcutils_ret) { \
if (rcutils_error_is_set()) { \
RCL_SET_ERROR_MSG(rcutils_get_error_string().str); \
} else { \
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("rcutils_ret_t code: %i", rcutils_ret); \
} \
} \
switch (rcutils_ret) { \
case RCUTILS_RET_OK: \
rcl_ret_var = RCL_RET_OK; \
break; \
case RCUTILS_RET_ERROR: \
rcl_ret_var = RCL_RET_ERROR; \
break; \
case RCUTILS_RET_BAD_ALLOC: \
rcl_ret_var = RCL_RET_BAD_ALLOC; \
break; \
case RCUTILS_RET_INVALID_ARGUMENT: \
rcl_ret_var = RCL_RET_INVALID_ARGUMENT; \
break; \
case RCUTILS_RET_NOT_INITIALIZED: \
rcl_ret_var = RCL_RET_NOT_INIT; \
break; \
default: \
rcl_ret_var = RCUTILS_RET_ERROR; \
} \
}

#ifdef __cplusplus
}
#endif
Expand Down
105 changes: 105 additions & 0 deletions rcl/include/rcl/subscription.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@ extern "C"
#include "rcl/macros.h"
#include "rcl/node.h"
#include "rcl/visibility_control.h"
#include "rcutils/types/string_array.h"

#include "rmw/message_sequence.h"

Expand Down Expand Up @@ -208,6 +209,110 @@ RCL_WARN_UNUSED
rcl_subscription_options_t
rcl_subscription_get_default_options(void);

/// Reclaim resources held inside rcl_subscription_options_t structure.
/**
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | No
* Uses Atomics | No
* Lock-Free | Yes
*
* \param[in] option The structure which its resources have to be deallocated.
* \return `RCL_RET_OK` if the memory was successfully freed, or
* \return `RCL_RET_INVALID_ARGUMENT` if option is NULL, or
* if its allocator is invalid and the structure contains initialized memory.
*/
RCL_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_subscription_options_fini(rcl_subscription_options_t * option);

/// Check if the content filtered topic feature is supported in the subscription.
/**
* Depending on the middleware and whether cft is supported in the subscription.
* this will return true if the middleware can support ContentFilteredTopic in the subscription.
*/
RCL_PUBLIC
RCL_WARN_UNUSED
bool
rcl_subscription_is_cft_supported(const rcl_subscription_t * subscription);

/// Set the filter expression and expression parameters for the subscription.
/**
* This function will set a filter expression and an array of expression parameters
* for the given subscription, but not to update the original rcl_subscription_options_t
* of subscription.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | No
* Thread-Safe | No
* Uses Atomics | Maybe [1]
* Lock-Free | Maybe [1]
*
* \param[in] subscription the subscription object to inspect.
* \param[in] filter_expression A filter_expression is a string that specifies the criteria
* to select the data samples of interest. It is similar to the WHERE part of an SQL clause.
* Using an empty("") string can reset/clean content filtered topic for the subscription.
* \param[in] expression_parameters An expression_parameters is an array of strings that
* give values to the ‘parameters’ (i.e., "%n" tokens begin from 0) in the filter_expression.
* The number of supplied parameters must fit with the requested values in the filter_expression.
* It can be NULL if there is no "%n" tokens placeholder in filter_expression.
* The maximun size allowance depends on concrete DDS vendor.
* (i.e., it cannot be greater than 100 on RTI_Connext.)
* \return `RCL_RET_OK` if the query was successful, or
* \return `RCL_RET_INVALID_ARGUMENT` if `subscription` is NULL, or
* \return `RCL_RET_INVALID_ARGUMENT` if `filter_expression` is NULL, or
* \return `RCL_RET_UNSUPPORTED` if the implementation does not support content filter topic, or
* \return `RCL_RET_ERROR` if an unspecified error occurs.
*/
RCL_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_subscription_set_cft_expression_parameters(
const rcl_subscription_t * subscription,
const char * filter_expression,
const rcutils_string_array_t * expression_parameters
);

/// Retrieve the filter expression of the subscription.
/**
* This function will return an filter expression by the given subscription.
*
* <hr>
* Attribute | Adherence
* ------------------ | -------------
* Allocates Memory | Yes
* Thread-Safe | No
* Uses Atomics | Maybe [1]
* Lock-Free | Maybe [1]
*
* \param[in] subscription the subscription object to inspect.
* \param[out] filter_expression an filter expression, populated on success.
* It is up to the caller to deallocate the filter expression later on,
* using rcutils_get_default_allocator().deallocate().
* \param[out] expression_parameters Array of expression parameters, populated on success.
* It is up to the caller to finalize this array later on, using rcutils_string_array_fini().
* \return `RCL_RET_OK` if the query was successful, or
* \return `RCL_RET_INVALID_ARGUMENT` if `subscription` is NULL, or
* \return `RCL_RET_INVALID_ARGUMENT` if `filter_expression` is NULL, or
* \return `RCL_RET_INVALID_ARGUMENT` if `expression_parameters` is NULL, or
* \return `RCL_RET_BAD_ALLOC` if memory allocation fails, or
* \return `RCL_RET_UNSUPPORTED` if the implementation does not support content filter topic, or
* \return `RCL_RET_ERROR` if an unspecified error occurs.
*/
RCL_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_subscription_get_cft_expression_parameters(
const rcl_subscription_t * subscription,
char ** filter_expression,
rcutils_string_array_t * expression_parameters
);

/// 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
Expand Down
2 changes: 1 addition & 1 deletion rcl/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>rcl</name>
<version>2.5.2</version>
<version>3.0.0</version>
<description>The ROS client library common implementation.
This package contains an API which builds on the ROS middleware API and is optionally built upon by the other ROS client libraries.
</description>
Expand Down
32 changes: 1 addition & 31 deletions rcl/src/rcl/logging_rosout.c
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,7 @@
#include "rcl/allocator.h"
#include "rcl/error_handling.h"
#include "rcl/logging_rosout.h"
#include "rcl/macros.h"
#include "rcl/node.h"
#include "rcl/publisher.h"
#include "rcl/time.h"
Expand Down Expand Up @@ -43,37 +44,6 @@ extern "C"
return RCL_RET_OK; \
}

#define RCL_RET_FROM_RCUTIL_RET(rcl_ret_var, rcutils_expr) \
{ \
rcutils_ret_t rcutils_ret = rcutils_expr; \
if (RCUTILS_RET_OK != rcutils_ret) { \
if (rcutils_error_is_set()) { \
RCL_SET_ERROR_MSG(rcutils_get_error_string().str); \
} else { \
RCL_SET_ERROR_MSG_WITH_FORMAT_STRING("rcutils_ret_t code: %i", rcutils_ret); \
} \
} \
switch (rcutils_ret) { \
case RCUTILS_RET_OK: \
rcl_ret_var = RCL_RET_OK; \
break; \
case RCUTILS_RET_ERROR: \
rcl_ret_var = RCL_RET_ERROR; \
break; \
case RCUTILS_RET_BAD_ALLOC: \
rcl_ret_var = RCL_RET_BAD_ALLOC; \
break; \
case RCUTILS_RET_INVALID_ARGUMENT: \
rcl_ret_var = RCL_RET_INVALID_ARGUMENT; \
break; \
case RCUTILS_RET_NOT_INITIALIZED: \
rcl_ret_var = RCL_RET_NOT_INIT; \
break; \
default: \
rcl_ret_var = RCUTILS_RET_ERROR; \
} \
}

typedef struct rosout_map_entry_t
{
rcl_node_t * node;
Expand Down
102 changes: 101 additions & 1 deletion rcl/src/rcl/subscription.c
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@ extern "C"
#include "rcl/error_handling.h"
#include "rcl/node.h"
#include "rcutils/logging_macros.h"
#include "rcutils/strdup.h"
#include "rcutils/types/string_array.h"
#include "rmw/error_handling.h"
#include "rmw/validate_full_topic_name.h"
#include "tracetools/tracetools.h"
Expand Down Expand Up @@ -92,6 +94,7 @@ rcl_subscription_init(
sizeof(rcl_subscription_impl_t), allocator->state);
RCL_CHECK_FOR_NULL_WITH_MSG(
subscription->impl, "allocating memory failed", ret = RCL_RET_BAD_ALLOC; goto cleanup);
subscription->impl->options = rcl_subscription_get_default_options();
// Fill out the implemenation struct.
// rmw_handle
// TODO(wjwwood): pass allocator once supported in rmw api.
Expand All @@ -115,8 +118,8 @@ rcl_subscription_init(
}
subscription->impl->actual_qos.avoid_ros_namespace_conventions =
options->qos.avoid_ros_namespace_conventions;
// options
subscription->impl->options = *options;

RCUTILS_LOG_DEBUG_NAMED(ROS_PACKAGE_NAME, "Subscription initialized");
ret = RCL_RET_OK;
TRACEPOINT(
Expand All @@ -138,6 +141,12 @@ rcl_subscription_init(
}
}

ret = rcl_subscription_options_fini(&subscription->impl->options);
if (RCL_RET_OK != ret) {
RCUTILS_SAFE_FWRITE_TO_STDERR(rmw_get_error_string().str);
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
}

allocator->deallocate(subscription->impl, allocator->state);
subscription->impl = NULL;
}
Expand Down Expand Up @@ -174,6 +183,13 @@ rcl_subscription_fini(rcl_subscription_t * subscription, rcl_node_t * node)
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
result = RCL_RET_ERROR;
}
rcl_ret_t rcl_ret = rcl_subscription_options_fini(&subscription->impl->options);
if (RCL_RET_OK != rcl_ret) {
RCUTILS_SAFE_FWRITE_TO_STDERR(rcl_get_error_string().str);
RCUTILS_SAFE_FWRITE_TO_STDERR("\n");
result = RCL_RET_ERROR;
}

allocator.deallocate(subscription->impl, allocator.state);
subscription->impl = NULL;
}
Expand All @@ -193,6 +209,90 @@ rcl_subscription_get_default_options()
return default_options;
}

RCL_PUBLIC
RCL_WARN_UNUSED
rcl_ret_t
rcl_subscription_options_fini(rcl_subscription_options_t * option)
{
RCL_CHECK_ARGUMENT_FOR_NULL(option, RCL_RET_INVALID_ARGUMENT);
// fini rmw_subscription_options_t
const rcl_allocator_t * allocator = &option->allocator;
RCL_CHECK_ALLOCATOR_WITH_MSG(allocator, "invalid allocator", return RCL_RET_INVALID_ARGUMENT);
if (option->rmw_subscription_options.filter_expression) {
allocator->deallocate(option->rmw_subscription_options.filter_expression, allocator->state);
option->rmw_subscription_options.filter_expression = NULL;
}

if (option->rmw_subscription_options.expression_parameters) {
rcutils_ret_t ret = rcutils_string_array_fini(
option->rmw_subscription_options.expression_parameters);
if (RCUTILS_RET_OK != ret) {
RCUTILS_SAFE_FWRITE_TO_STDERR("Failed to fini string array.\n");
}
allocator->deallocate(option->rmw_subscription_options.expression_parameters, allocator->state);
option->rmw_subscription_options.expression_parameters = NULL;
}
return RCL_RET_OK;
}

bool
rcl_subscription_is_cft_supported(const rcl_subscription_t * subscription)
{
if (!rcl_subscription_is_valid(subscription)) {
return false;
}
return subscription->impl->rmw_handle->is_cft_supported;
}

rcl_ret_t
rcl_subscription_set_cft_expression_parameters(
const rcl_subscription_t * subscription,
const char * filter_expression,
const rcutils_string_array_t * expression_parameters
)
{
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_SUBSCRIPTION_INVALID);
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);

if (!rcl_subscription_is_valid(subscription)) {
return RCL_RET_SUBSCRIPTION_INVALID;
}
RCL_CHECK_ARGUMENT_FOR_NULL(filter_expression, RCL_RET_INVALID_ARGUMENT);
rmw_ret_t ret = rmw_subscription_set_cft_expression_parameters(
subscription->impl->rmw_handle, filter_expression, expression_parameters);

if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return rcl_convert_rmw_ret_to_rcl_ret(ret);
}
return RCL_RET_OK;
}

rcl_ret_t
rcl_subscription_get_cft_expression_parameters(
const rcl_subscription_t * subscription,
char ** filter_expression,
rcutils_string_array_t * expression_parameters
)
{
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_SUBSCRIPTION_INVALID);
RCUTILS_CAN_RETURN_WITH_ERROR_OF(RCL_RET_INVALID_ARGUMENT);

if (!rcl_subscription_is_valid(subscription)) {
return RCL_RET_SUBSCRIPTION_INVALID;
}
RCL_CHECK_ARGUMENT_FOR_NULL(filter_expression, RCL_RET_INVALID_ARGUMENT);
RCL_CHECK_ARGUMENT_FOR_NULL(expression_parameters, RCL_RET_INVALID_ARGUMENT);
rmw_ret_t ret = rmw_subscription_get_cft_expression_parameters(
subscription->impl->rmw_handle, filter_expression, expression_parameters);

if (ret != RMW_RET_OK) {
RCL_SET_ERROR_MSG(rmw_get_error_string().str);
return rcl_convert_rmw_ret_to_rcl_ret(ret);
}
return RCL_RET_OK;
}

rcl_ret_t
rcl_take(
const rcl_subscription_t * subscription,
Expand Down
Loading