1313// limitations under the License.
1414
1515#include < pybind11/pybind11.h>
16+ #include < pybind11/stl.h>
1617
1718#include < rcl/error_handling.h>
1819#include < rcl/node.h>
2122#include < rosidl_runtime_c/message_type_support_struct.h>
2223#include < rmw/types.h>
2324
25+ #include < cstddef>
2426#include < memory>
2527#include < stdexcept>
2628#include < string>
2729#include < utility>
30+ #include < vector>
31+
32+ #include < rcpputils/scope_exit.hpp>
2833
2934#include " exceptions.hpp"
3035#include " node.hpp"
@@ -39,9 +44,25 @@ namespace rclpy
3944{
4045using events_executor::RclEventCallbackTrampoline;
4146
47+ namespace
48+ {
49+ std::vector<const char *>
50+ get_c_vector_string (const std::vector<std::string> & strings_in)
51+ {
52+ std::vector<const char *> cstrings;
53+ cstrings.reserve (strings_in.size ());
54+
55+ for (size_t i = 0 ; i < strings_in.size (); ++i) {
56+ cstrings.push_back (strings_in[i].c_str ());
57+ }
58+
59+ return cstrings;
60+ }
61+ } // namespace
62+
4263Subscription::Subscription (
4364 Node & node, py::object pymsg_type, std::string topic,
44- py::object pyqos_profile)
65+ py::object pyqos_profile, py::object content_filter_options )
4566: node_(node)
4667{
4768 auto msg_type = static_cast <rosidl_message_type_support_t *>(
@@ -75,6 +96,24 @@ Subscription::Subscription(
7596
7697 *rcl_subscription_ = rcl_get_zero_initialized_subscription ();
7798
99+ std::string filter_expression;
100+ std::vector<std::string> expression_parameters;
101+ if (!content_filter_options.is_none ()) {
102+ filter_expression = content_filter_options.attr (" filter_expression" ).cast <std::string>();
103+ expression_parameters =
104+ content_filter_options.attr (" expression_parameters" ).cast <std::vector<std::string>>();
105+ std::vector<const char *> cstrings =
106+ get_c_vector_string (expression_parameters);
107+ rcl_ret_t ret = rcl_subscription_options_set_content_filter_options (
108+ filter_expression.c_str (),
109+ cstrings.size (),
110+ cstrings.data (),
111+ &subscription_ops);
112+ if (RCL_RET_OK != ret) {
113+ throw rclpy::RCLError (" Failed to set content_filter_options" );
114+ }
115+ }
116+
78117 rcl_ret_t ret = rcl_subscription_init (
79118 rcl_subscription_.get (), node_.rcl_ptr (), msg_type,
80119 topic.c_str (), &subscription_ops);
@@ -237,11 +276,98 @@ Subscription::clear_on_new_message_callback()
237276 }
238277}
239278
279+ bool
280+ Subscription::is_cft_enabled () const
281+ {
282+ return rcl_subscription_is_cft_enabled (rcl_subscription_.get ());
283+ }
284+
285+ void
286+ Subscription::set_content_filter (
287+ const std::string & filter_expression,
288+ const std::vector<std::string> & expression_parameters)
289+ {
290+ rcl_subscription_content_filter_options_t options =
291+ rcl_get_zero_initialized_subscription_content_filter_options ();
292+ std::vector<const char *> cstrings = get_c_vector_string (expression_parameters);
293+ rcl_ret_t ret = rcl_subscription_content_filter_options_init (
294+ rcl_subscription_.get (),
295+ filter_expression.c_str (),
296+ cstrings.size (),
297+ cstrings.data (),
298+ &options);
299+ if (RCL_RET_OK != ret) {
300+ throw RCLError (" Failed to init subscription content_filtered_topic option" );
301+ }
302+
303+ RCPPUTILS_SCOPE_EXIT (
304+ {
305+ rcl_ret_t ret = rcl_subscription_content_filter_options_fini (
306+ rcl_subscription_.get (), &options);
307+ if (RCL_RET_OK != ret) {
308+ throw RCLError (
309+ " Failed to fini subscription content_filtered_topic option: " +
310+ std::string (rcl_get_error_string ().str ));
311+ }
312+ });
313+
314+ ret = rcl_subscription_set_content_filter (
315+ rcl_subscription_.get (),
316+ &options);
317+ if (RCL_RET_OK != ret) {
318+ throw RCLError (" Failed to set cft expression parameters" );
319+ }
320+ }
321+
322+ py::object
323+ Subscription::get_content_filter () const
324+ {
325+ rcl_subscription_content_filter_options_t options =
326+ rcl_get_zero_initialized_subscription_content_filter_options ();
327+
328+ rcl_ret_t ret = rcl_subscription_get_content_filter (
329+ rcl_subscription_.get (),
330+ &options);
331+ if (RCL_RET_OK != ret) {
332+ throw RCLError (" Failed to get cft expression parameters" );
333+ }
334+
335+ RCPPUTILS_SCOPE_EXIT (
336+ {
337+ rcl_ret_t ret = rcl_subscription_content_filter_options_fini (
338+ rcl_subscription_.get (), &options);
339+ if (RCL_RET_OK != ret) {
340+ throw RCLError (
341+ " Failed to fini subscription content_filtered_topic option: " +
342+ std::string (rcl_get_error_string ().str ));
343+ }
344+ });
345+
346+ rmw_subscription_content_filter_options_t & content_filter_options =
347+ options.rmw_subscription_content_filter_options ;
348+ std::vector<std::string> expression_parameters;
349+ for (size_t i = 0 ; i < content_filter_options.expression_parameters .size ; ++i) {
350+ expression_parameters.push_back (content_filter_options.expression_parameters .data [i]);
351+ }
352+
353+ py::object content_filter_options_class =
354+ py::module_::import (" rclpy.subscription_content_filter_options" ).attr (" ContentFilterOptions" );
355+
356+ return content_filter_options_class (
357+ std::string (content_filter_options.filter_expression ),
358+ expression_parameters);
359+ }
360+
240361void
241362define_subscription (py::object module )
242363{
243364 py::class_<Subscription, Destroyable, std::shared_ptr<Subscription>>(module , " Subscription" )
244- .def (py::init<Node &, py::object, std::string, py::object>())
365+ .def (py::init<Node &, py::object, std::string, py::object, py::object>(),
366+ py::arg (" node" ),
367+ py::arg (" msg_type" ),
368+ py::arg (" topic" ),
369+ py::arg (" qos_profile" ),
370+ py::arg (" content_filter_options" ) = py::none ())
245371 .def_property_readonly (
246372 " pointer" , [](const Subscription & subscription) {
247373 return reinterpret_cast <size_t >(subscription.rcl_ptr ());
@@ -262,6 +388,14 @@ define_subscription(py::object module)
262388 .def (
263389 " set_on_new_message_callback" , &Subscription::set_on_new_message_callback,
264390 py::arg (" callback" ))
265- .def (" clear_on_new_message_callback" , &Subscription::clear_on_new_message_callback);
391+ .def (" clear_on_new_message_callback" , &Subscription::clear_on_new_message_callback)
392+ .def (" is_cft_enabled" , &Subscription::is_cft_enabled,
393+ " Check if content filtering is enabled for this subscription." )
394+ .def (
395+ " set_content_filter" , &Subscription::set_content_filter,
396+ " Set the filter expression and expression parameters for the subscription." )
397+ .def (
398+ " get_content_filter" , &Subscription::get_content_filter,
399+ " Get the filter expression and expression parameters for the subscription." );
266400}
267401} // namespace rclpy
0 commit comments