Skip to content

Commit 9ff80f5

Browse files
authored
add ContentFilteredTopic example. (#341)
1 parent 7d6f14a commit 9ff80f5

File tree

3 files changed

+109
-0
lines changed

3 files changed

+109
-0
lines changed

rclcpp/topics/minimal_subscriber/CMakeLists.txt

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -33,6 +33,8 @@ ament_target_dependencies(subscriber_member_function_with_unique_network_flow_en
3333
add_executable(subscriber_not_composable not_composable.cpp)
3434
ament_target_dependencies(subscriber_not_composable rclcpp std_msgs)
3535

36+
add_executable(subscriber_content_filtering content_filtering.cpp)
37+
ament_target_dependencies(subscriber_content_filtering rclcpp std_msgs)
3638

3739
add_library(wait_set_subscriber_library SHARED
3840
wait_set_subscriber.cpp
@@ -65,6 +67,7 @@ install(TARGETS
6567
subscriber_member_function_with_type_adapter
6668
subscriber_member_function_with_unique_network_flow_endpoints
6769
subscriber_not_composable
70+
subscriber_content_filtering
6871
DESTINATION lib/${PROJECT_NAME})
6972

7073
if(BUILD_TESTING)

rclcpp/topics/minimal_subscriber/README.md

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,7 @@ This package contains a few different strategies for creating nodes which receiv
88
* `static_wait_set_subscriber.cpp` uses a `rclcpp::StaticWaitSet` to wait and poll for data
99
* `time_triggered_wait_set_subscriber.cpp` uses a `rclcpp::Waitset` and a timer to poll for data
1010
periodically
11+
* `content_filtering.cpp` uses the content filtering feature for Subscriptions
1112

1213
Note that `not_composable.cpp` instantiates a `rclcpp::Node` _without_ subclassing it.
1314
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
2021
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.
2122
This is not a common use case in ROS 2 so this is not the recommended strategy to use by-default.
2223
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.
24+
25+
The example `content_filtering.cpp` shows how to use the content filtering feature for Subscriptions.
Lines changed: 103 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,103 @@
1+
// Copyright 2022 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <functional>
16+
#include <memory>
17+
#include <string>
18+
19+
#include "rclcpp/rclcpp.hpp"
20+
#include "std_msgs/msg/string.hpp"
21+
22+
using std::placeholders::_1;
23+
24+
class MinimalContentFilteringSubscriber : public rclcpp::Node
25+
{
26+
public:
27+
MinimalContentFilteringSubscriber()
28+
: Node("minimal_contentfiltering_subscriber"),
29+
current_filtering_expression_("data = %0"),
30+
current_expression_parameter_("'Hello, world! 1'"),
31+
count_(10)
32+
{
33+
rclcpp::SubscriptionOptions sub_options;
34+
current_expression_parameter_ = "'Hello, world! " + std::to_string(count_) + "'";
35+
sub_options.content_filter_options.filter_expression = current_filtering_expression_;
36+
sub_options.content_filter_options.expression_parameters = {
37+
current_expression_parameter_
38+
};
39+
40+
subscription_ = this->create_subscription<std_msgs::msg::String>(
41+
"topic", 10, std::bind(&MinimalContentFilteringSubscriber::topic_callback, this, _1),
42+
sub_options);
43+
44+
if (!subscription_->is_cft_enabled()) {
45+
RCLCPP_WARN(
46+
this->get_logger(), "Content filter is not enabled since it's not supported");
47+
} else {
48+
RCLCPP_INFO(
49+
this->get_logger(),
50+
"Subscribed to topic \"%s\" with content filtering", subscription_->get_topic_name());
51+
print_expression_parameter();
52+
}
53+
}
54+
55+
private:
56+
void topic_callback(const std_msgs::msg::String & msg)
57+
{
58+
RCLCPP_INFO(this->get_logger(), "I heard: '%s'", msg.data.c_str());
59+
// update filtering expression parameter
60+
if (subscription_->is_cft_enabled()) {
61+
count_ = count_ + 10;
62+
current_expression_parameter_ = "'Hello, world! " + std::to_string(count_) + "'";
63+
try {
64+
subscription_->set_content_filter(
65+
current_filtering_expression_, {current_expression_parameter_}
66+
);
67+
} catch (const std::exception & e) {
68+
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
69+
}
70+
}
71+
print_expression_parameter();
72+
}
73+
74+
void print_expression_parameter(void) const
75+
{
76+
// print filtering expression and parameter stored in subscription
77+
if (subscription_->is_cft_enabled()) {
78+
rclcpp::ContentFilterOptions options;
79+
try {
80+
options = subscription_->get_content_filter();
81+
RCLCPP_INFO(
82+
this->get_logger(),
83+
"Content filtering expression and parameter are \"%s\" and \"%s\"",
84+
options.filter_expression.c_str(), options.expression_parameters[0].c_str());
85+
} catch (const std::exception & e) {
86+
RCLCPP_ERROR(this->get_logger(), "%s", e.what());
87+
}
88+
}
89+
}
90+
91+
rclcpp::Subscription<std_msgs::msg::String>::SharedPtr subscription_;
92+
std::string current_filtering_expression_;
93+
std::string current_expression_parameter_;
94+
size_t count_;
95+
};
96+
97+
int main(int argc, char * argv[])
98+
{
99+
rclcpp::init(argc, argv);
100+
rclcpp::spin(std::make_shared<MinimalContentFilteringSubscriber>());
101+
rclcpp::shutdown();
102+
return 0;
103+
}

0 commit comments

Comments
 (0)