19
19
#include < utility>
20
20
#include < vector>
21
21
22
- #include " rclcpp/parameter_event_monitor .hpp"
22
+ #include " rclcpp/parameter_event_handler .hpp"
23
23
#include " rcpputils/join.hpp"
24
24
25
25
namespace rclcpp
26
26
{
27
27
28
28
ParameterEventCallbackHandle::SharedPtr
29
- ParameterEventMonitor ::add_parameter_event_callback (
29
+ ParameterEventHandler ::add_parameter_event_callback (
30
30
ParameterEventCallbackType callback)
31
31
{
32
32
std::lock_guard<std::recursive_mutex> lock (mutex_);
@@ -55,7 +55,7 @@ struct HandleCompare
55
55
};
56
56
57
57
void
58
- ParameterEventMonitor ::remove_parameter_event_callback (
58
+ ParameterEventHandler ::remove_parameter_event_callback (
59
59
const ParameterEventCallbackHandle * const handle)
60
60
{
61
61
std::lock_guard<std::recursive_mutex> lock (mutex_);
@@ -71,7 +71,7 @@ ParameterEventMonitor::remove_parameter_event_callback(
71
71
}
72
72
73
73
ParameterCallbackHandle::SharedPtr
74
- ParameterEventMonitor ::add_parameter_callback (
74
+ ParameterEventHandler ::add_parameter_callback (
75
75
const std::string & parameter_name,
76
76
ParameterCallbackType callback,
77
77
const std::string & node_name)
@@ -90,7 +90,7 @@ ParameterEventMonitor::add_parameter_callback(
90
90
}
91
91
92
92
void
93
- ParameterEventMonitor ::remove_parameter_callback (
93
+ ParameterEventHandler ::remove_parameter_callback (
94
94
const ParameterCallbackHandle * const handle)
95
95
{
96
96
std::lock_guard<std::recursive_mutex> lock (mutex_);
@@ -110,7 +110,7 @@ ParameterEventMonitor::remove_parameter_callback(
110
110
}
111
111
112
112
bool
113
- ParameterEventMonitor ::get_parameter_from_event (
113
+ ParameterEventHandler ::get_parameter_from_event (
114
114
const rcl_interfaces::msg::ParameterEvent & event,
115
115
rclcpp::Parameter & parameter,
116
116
const std::string parameter_name,
@@ -138,7 +138,7 @@ ParameterEventMonitor::get_parameter_from_event(
138
138
}
139
139
140
140
rclcpp::Parameter
141
- ParameterEventMonitor ::get_parameter_from_event (
141
+ ParameterEventHandler ::get_parameter_from_event (
142
142
const rcl_interfaces::msg::ParameterEvent & event,
143
143
const std::string parameter_name,
144
144
const std::string node_name)
@@ -153,7 +153,7 @@ ParameterEventMonitor::get_parameter_from_event(
153
153
}
154
154
155
155
std::vector<rclcpp::Parameter>
156
- ParameterEventMonitor ::get_parameters_from_event (
156
+ ParameterEventHandler ::get_parameters_from_event (
157
157
const rcl_interfaces::msg::ParameterEvent & event)
158
158
{
159
159
std::vector<rclcpp::Parameter> params;
@@ -170,7 +170,7 @@ ParameterEventMonitor::get_parameters_from_event(
170
170
}
171
171
172
172
void
173
- ParameterEventMonitor ::event_callback (
173
+ ParameterEventHandler ::event_callback (
174
174
const rcl_interfaces::msg::ParameterEvent::SharedPtr event)
175
175
{
176
176
std::lock_guard<std::recursive_mutex> lock (mutex_);
@@ -200,7 +200,7 @@ ParameterEventMonitor::event_callback(
200
200
}
201
201
202
202
std::string
203
- ParameterEventMonitor ::resolve_path (const std::string & path)
203
+ ParameterEventHandler ::resolve_path (const std::string & path)
204
204
{
205
205
std::string full_path;
206
206
0 commit comments