diff --git a/rclcpp/topics/minimal_subscriber/CMakeLists.txt b/rclcpp/topics/minimal_subscriber/CMakeLists.txt index 2edca97f..617c7001 100644 --- a/rclcpp/topics/minimal_subscriber/CMakeLists.txt +++ b/rclcpp/topics/minimal_subscriber/CMakeLists.txt @@ -33,6 +33,8 @@ ament_target_dependencies(subscriber_member_function_with_unique_network_flow_en add_executable(subscriber_not_composable not_composable.cpp) ament_target_dependencies(subscriber_not_composable rclcpp std_msgs) +add_executable(subscriber_content_filtering content_filtering.cpp) +ament_target_dependencies(subscriber_content_filtering rclcpp std_msgs) add_library(wait_set_subscriber_library SHARED wait_set_subscriber.cpp @@ -65,6 +67,7 @@ install(TARGETS subscriber_member_function_with_type_adapter subscriber_member_function_with_unique_network_flow_endpoints subscriber_not_composable + subscriber_content_filtering DESTINATION lib/${PROJECT_NAME}) if(BUILD_TESTING) diff --git a/rclcpp/topics/minimal_subscriber/README.md b/rclcpp/topics/minimal_subscriber/README.md index 5caa8006..fb03cf69 100644 --- a/rclcpp/topics/minimal_subscriber/README.md +++ b/rclcpp/topics/minimal_subscriber/README.md @@ -8,6 +8,7 @@ This package contains a few different strategies for creating nodes which receiv * `static_wait_set_subscriber.cpp` uses a `rclcpp::StaticWaitSet` to wait and poll for data * `time_triggered_wait_set_subscriber.cpp` uses a `rclcpp::Waitset` and a timer to poll for data periodically + * `content_filtering.cpp` uses the content filtering feature for Subscriptions Note that `not_composable.cpp` instantiates a `rclcpp::Node` _without_ subclassing it. This was the typical usage model in ROS 1, but this style of coding is not compatible with composing multiple nodes into a single process. @@ -20,3 +21,5 @@ We provide multiple examples of different coding styles which achieve this behav The following examples `wait_set_subscriber.cpp`, `static_wait_set_subscriber.cpp` and `time_triggered_wait_set_subscriber.cpp` show how to use a subscription in a node using a `rclcpp` wait-set. This is not a common use case in ROS 2 so this is not the recommended strategy to use by-default. This strategy makes sense in some specific situations, for example when the developer needs to have more control over callback order execution, to create custom triggering conditions or to use the timeouts provided by the wait-sets. + +The example `content_filtering.cpp` shows how to use the content filtering feature for Subscriptions. diff --git a/rclcpp/topics/minimal_subscriber/content_filtering.cpp b/rclcpp/topics/minimal_subscriber/content_filtering.cpp new file mode 100644 index 00000000..74de76e4 --- /dev/null +++ b/rclcpp/topics/minimal_subscriber/content_filtering.cpp @@ -0,0 +1,103 @@ +// Copyright 2022 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. + +#include +#include +#include + +#include "rclcpp/rclcpp.hpp" +#include "std_msgs/msg/string.hpp" + +using std::placeholders::_1; + +class MinimalContentFilteringSubscriber : public rclcpp::Node +{ +public: + MinimalContentFilteringSubscriber() + : Node("minimal_contentfiltering_subscriber"), + current_filtering_expression_("data = %0"), + current_expression_parameter_("'Hello, world! 1'"), + count_(10) + { + rclcpp::SubscriptionOptions sub_options; + current_expression_parameter_ = "'Hello, world! " + std::to_string(count_) + "'"; + sub_options.content_filter_options.filter_expression = current_filtering_expression_; + sub_options.content_filter_options.expression_parameters = { + current_expression_parameter_ + }; + + subscription_ = this->create_subscription( + "topic", 10, std::bind(&MinimalContentFilteringSubscriber::topic_callback, this, _1), + sub_options); + + if (!subscription_->is_cft_enabled()) { + RCLCPP_WARN( + this->get_logger(), "Content filter is not enabled since it's not supported"); + } else { + RCLCPP_INFO( + this->get_logger(), + "Subscribed to topic \"%s\" with content filtering", subscription_->get_topic_name()); + print_expression_parameter(); + } + } + +private: + void topic_callback(const std_msgs::msg::String & msg) + { + RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str()); + // update filtering expression parameter + if (subscription_->is_cft_enabled()) { + count_ = count_ + 10; + current_expression_parameter_ = "'Hello, world! " + std::to_string(count_) + "'"; + try { + subscription_->set_content_filter( + current_filtering_expression_, {current_expression_parameter_} + ); + } catch (const std::exception & e) { + RCLCPP_ERROR(this->get_logger(), "%s", e.what()); + } + } + print_expression_parameter(); + } + + void print_expression_parameter(void) const + { + // print filtering expression and parameter stored in subscription + if (subscription_->is_cft_enabled()) { + rclcpp::ContentFilterOptions options; + try { + options = subscription_->get_content_filter(); + RCLCPP_INFO( + this->get_logger(), + "Content filtering expression and parameter are \"%s\" and \"%s\"", + options.filter_expression.c_str(), options.expression_parameters[0].c_str()); + } catch (const std::exception & e) { + RCLCPP_ERROR(this->get_logger(), "%s", e.what()); + } + } + } + + rclcpp::Subscription::SharedPtr subscription_; + std::string current_filtering_expression_; + std::string current_expression_parameter_; + size_t count_; +}; + +int main(int argc, char * argv[]) +{ + rclcpp::init(argc, argv); + rclcpp::spin(std::make_shared()); + rclcpp::shutdown(); + return 0; +}