Skip to content

Commit

Permalink
remove the implementation temporary, add them with fallback in the fe…
Browse files Browse the repository at this point in the history
…ature

1. add DEFINE_CONTENT_FILTER with default(ON) to build content filter interfaces
2. user need a compile option(CONTENT_FILTER_ENABLE) to turn on the feature
to set the filter or call the interfaces

Signed-off-by: Chen Lihui <[email protected]>
  • Loading branch information
Chen Lihui committed Mar 24, 2022
1 parent 43c59e8 commit e72216e
Show file tree
Hide file tree
Showing 8 changed files with 18 additions and 349 deletions.
5 changes: 5 additions & 0 deletions rclcpp/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@ cmake_minimum_required(VERSION 3.12)

project(rclcpp)

option(DEFINE_CONTENT_FILTER "Content filter feature support" ON)
if(DEFINE_CONTENT_FILTER)
add_definitions(-DCONTENT_FILTER_ENABLE)
endif()

find_package(Threads REQUIRED)

find_package(ament_cmake_ros REQUIRED)
Expand Down
10 changes: 2 additions & 8 deletions rclcpp/include/rclcpp/subscription_base.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -491,14 +491,7 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
event_handlers_[event_type]->clear_on_ready_callback();
}

/// Check if content filtered topic feature of the subscription instance is enabled.
/**
* \return boolean flag indicating if the content filtered topic of this subscription is enabled.
*/
RCLCPP_PUBLIC
bool
is_cft_enabled() const;

#ifdef CONTENT_FILTER_ENABLE
/// Set the filter expression and expression parameters for the subscription.
/**
* \param[in] filter_expression An filter expression to set.
Expand Down Expand Up @@ -528,6 +521,7 @@ class SubscriptionBase : public std::enable_shared_from_this<SubscriptionBase>
get_content_filter(
std::string & filter_expression,
std::vector<std::string> & expression_parameters) const;
#endif // CONTENT_FILTER_ENABLE

protected:
template<typename EventCallbackT>
Expand Down
17 changes: 2 additions & 15 deletions rclcpp/include/rclcpp/subscription_options.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,7 @@ struct SubscriptionOptionsBase

QosOverridingOptions qos_overriding_options;

#ifdef CONTENT_FILTER_ENABLE
/// Options to configure content filtered topic in the subscription.
struct ContentFilterOptions
{
Expand All @@ -95,6 +96,7 @@ struct SubscriptionOptionsBase
};

ContentFilterOptions content_filter_options;
#endif // CONTENT_FILTER_ENABLE
};

/// Structure containing optional configuration for Subscriptions.
Expand Down Expand Up @@ -137,21 +139,6 @@ struct SubscriptionOptionsWithAllocator : public SubscriptionOptionsBase
rmw_implementation_payload->modify_rmw_subscription_options(result.rmw_subscription_options);
}

// Copy content_filter_options into rcl_subscription_options.
if (!content_filter_options.filter_expression.empty()) {
std::vector<const char *> cstrings =
get_c_vector_string(content_filter_options.expression_parameters);
rcl_ret_t ret = rcl_subscription_options_set_content_filter_options(
get_c_string(content_filter_options.filter_expression),
cstrings.size(),
cstrings.data(),
&result);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(
ret, "failed to set content_filter_options");
}
}

return result;
}

Expand Down
9 changes: 0 additions & 9 deletions rclcpp/include/rclcpp/utilities.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -321,15 +321,6 @@ RCLCPP_PUBLIC
const char *
get_c_string(const std::string & string_in);

/// Return the std::vector of C string from the given std::vector<std::string>.
/**
* \param[in] string_in is a std::string
* \return the std::vector of C string from the std::vector<std::string>
*/
RCLCPP_PUBLIC
std::vector<const char *>
get_c_vector_string(const std::vector<std::string> & strings);

} // namespace rclcpp

#endif // RCLCPP__UTILITIES_HPP_
3 changes: 0 additions & 3 deletions rclcpp/include/rclcpp/wait_for_message.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -59,9 +59,6 @@ bool wait_for_message(
RCPPUTILS_SCOPE_EXIT(wait_set.remove_subscription(subscription); );
wait_set.add_guard_condition(gc);
auto ret = wait_set.wait(time_to_wait);
// if it is fixed in other PR, remove them and rebase.
wait_set.remove_subscription(subscription);
wait_set.remove_guard_condition(gc);
if (ret.kind() != rclcpp::WaitResultKind::Ready) {
return false;
}
Expand Down
81 changes: 8 additions & 73 deletions rclcpp/src/rclcpp/subscription_base.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,8 +20,6 @@
#include <unordered_map>
#include <vector>

#include "rcpputils/scope_exit.hpp"

#include "rclcpp/exceptions.hpp"
#include "rclcpp/expand_topic_or_service_name.hpp"
#include "rclcpp/experimental/intra_process_manager.hpp"
Expand Down Expand Up @@ -357,89 +355,26 @@ SubscriptionBase::set_on_new_message_callback(
}
}

bool
SubscriptionBase::is_cft_enabled() const
{
return rcl_subscription_is_cft_enabled(subscription_handle_.get());
}

#ifdef CONTENT_FILTER_ENABLE
void
SubscriptionBase::set_content_filter(
const std::string & filter_expression,
const std::vector<std::string> & expression_parameters)
{
rcl_subscription_content_filter_options_t options =
rcl_subscription_get_default_content_filter_options();

std::vector<const char *> cstrings =
get_c_vector_string(expression_parameters);
rcl_ret_t ret = rcl_subscription_content_filter_options_init(
get_c_string(filter_expression),
cstrings.size(),
cstrings.data(),
&options);
if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(
ret, "failed to init subscription content_filtered_topic option");
}
RCPPUTILS_SCOPE_EXIT(
{
rcl_ret_t ret = rcl_subscription_content_filter_options_fini(&options);
if (RCL_RET_OK != ret) {
RCLCPP_ERROR(
rclcpp::get_logger("rclcpp"),
"Failed to fini subscription content_filtered_topic option: %s",
rcl_get_error_string().str);
rcl_reset_error();
}
});
static_cast<void>(filter_expression);
static_cast<void>(expression_parameters);

ret = rcl_subscription_set_content_filter(
subscription_handle_.get(),
&options);

if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to set cft expression parameters");
}
rclcpp::exceptions::throw_from_rcl_error(RMW_RET_UNSUPPORTED, "content filter unsupported");
}

void
SubscriptionBase::get_content_filter(
std::string & filter_expression,
std::vector<std::string> & expression_parameters) const
{
rcl_subscription_content_filter_options_t options =
rcl_subscription_get_default_content_filter_options();

// use rcl_content_filter_options_t instead of char * and
rcl_ret_t ret = rcl_subscription_get_content_filter(
subscription_handle_.get(),
&options);
static_cast<void>(filter_expression);
static_cast<void>(expression_parameters);

if (RCL_RET_OK != ret) {
rclcpp::exceptions::throw_from_rcl_error(ret, "failed to get cft expression parameters");
}

RCPPUTILS_SCOPE_EXIT(
{
rcl_ret_t ret = rcl_subscription_content_filter_options_fini(&options);
if (RCL_RET_OK != ret) {
RCLCPP_ERROR(
rclcpp::get_logger("rclcpp"),
"Failed to fini subscription content_filtered_topic option: %s",
rcl_get_error_string().str);
rcl_reset_error();
}
});

rmw_subscription_content_filter_options_t * content_filter_options =
options.rmw_subscription_content_filter_options;
if (content_filter_options->filter_expression) {
filter_expression = content_filter_options->filter_expression;
}

for (size_t i = 0; i < content_filter_options->expression_parameters.size; ++i) {
expression_parameters.push_back(
content_filter_options->expression_parameters.data[i]);
}
rclcpp::exceptions::throw_from_rcl_error(RMW_RET_UNSUPPORTED, "content filter unsupported");
}
#endif // CONTENT_FILTER_ENABLE
13 changes: 0 additions & 13 deletions rclcpp/src/rclcpp/utilities.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -214,17 +214,4 @@ get_c_string(const std::string & string_in)
return string_in.c_str();
}

std::vector<const char *>
get_c_vector_string(const std::vector<std::string> & strings)
{
std::vector<const char *> cstrings;
cstrings.reserve(strings.size());

for (size_t i = 0; i < strings.size(); ++i) {
cstrings.push_back(strings[i].c_str());
}

return cstrings;
}

} // namespace rclcpp
Loading

0 comments on commit e72216e

Please sign in to comment.