forked from ros2/rclcpp
-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathparameter_events_filter.cpp
More file actions
61 lines (56 loc) · 2.14 KB
/
parameter_events_filter.cpp
File metadata and controls
61 lines (56 loc) · 2.14 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
// Copyright 2017 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 "rclcpp/parameter_events_filter.hpp"
#include <memory>
#include <string>
#include <vector>
using rclcpp::ParameterEventsFilter;
using EventType = rclcpp::ParameterEventsFilter::EventType;
using EventPair = rclcpp::ParameterEventsFilter::EventPair;
ParameterEventsFilter::ParameterEventsFilter(
std::shared_ptr<const rcl_interfaces::msg::ParameterEvent> event,
const std::vector<std::string> & names,
const std::vector<EventType> & types)
: event_(event)
{
if (std::find(types.begin(), types.end(), EventType::NEW) != types.end()) {
for (auto & new_parameter : event->new_parameters) {
if (std::find(names.begin(), names.end(), new_parameter.name) != names.end()) {
result_.push_back(
EventPair(EventType::NEW, &new_parameter));
}
}
}
if (std::find(types.begin(), types.end(), EventType::CHANGED) != types.end()) {
for (auto & changed_parameter : event->changed_parameters) {
if (std::find(names.begin(), names.end(), changed_parameter.name) != names.end()) {
result_.push_back(
EventPair(EventType::CHANGED, &changed_parameter));
}
}
}
if (std::find(types.begin(), types.end(), EventType::DELETED) != types.end()) {
for (auto & deleted_parameter : event->deleted_parameters) {
if (std::find(names.begin(), names.end(), deleted_parameter.name) != names.end()) {
result_.push_back(
EventPair(EventType::DELETED, &deleted_parameter));
}
}
}
}
const std::vector<EventPair> &
ParameterEventsFilter::get_events() const
{
return result_;
}