ROS 2 rclcpp + rcl - rolling  rolling-a919a6e5
ROS 2 C++ Client Library with ROS Client Library
parameter_events_filter.cpp
1 // Copyright 2017 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 "rclcpp/parameter_events_filter.hpp"
16 
17 #include <memory>
18 #include <string>
19 #include <vector>
20 
22 using EventType = rclcpp::ParameterEventsFilter::EventType;
24 
25 ParameterEventsFilter::ParameterEventsFilter(
26  std::shared_ptr<const rcl_interfaces::msg::ParameterEvent> event,
27  const std::vector<std::string> & names,
28  const std::vector<EventType> & types)
29 : event_(event)
30 {
31  if (!event) {
32  throw std::invalid_argument("event cannot be null");
33  }
34  if (std::find(types.begin(), types.end(), EventType::NEW) != types.end()) {
35  for (auto & new_parameter : event->new_parameters) {
36  if (std::find(names.begin(), names.end(), new_parameter.name) != names.end()) {
37  result_.push_back(
38  EventPair(EventType::NEW, &new_parameter));
39  }
40  }
41  }
42  if (std::find(types.begin(), types.end(), EventType::CHANGED) != types.end()) {
43  for (auto & changed_parameter : event->changed_parameters) {
44  if (std::find(names.begin(), names.end(), changed_parameter.name) != names.end()) {
45  result_.push_back(
46  EventPair(EventType::CHANGED, &changed_parameter));
47  }
48  }
49  }
50  if (std::find(types.begin(), types.end(), EventType::DELETED) != types.end()) {
51  for (auto & deleted_parameter : event->deleted_parameters) {
52  if (std::find(names.begin(), names.end(), deleted_parameter.name) != names.end()) {
53  result_.push_back(
54  EventPair(EventType::DELETED, &deleted_parameter));
55  }
56  }
57  }
58 }
59 
60 const std::vector<EventPair> &
62 {
63  return result_;
64 }
RCLCPP_PUBLIC const std::vector< EventPair > & get_events() const
Get the result of the filter.
std::pair< EventType, const rcl_interfaces::msg::Parameter * > EventPair
Used for the listed results.