22
22
#define FMT_HEADER_ONLY
23
23
#include < fmt/format.h>
24
24
25
+ #include < sstream>
26
+
25
27
namespace
26
28
{
27
29
std::vector<std::string> split (const std::string & str, const char delim)
@@ -37,7 +39,7 @@ std::vector<std::string> split(const std::string & str, const char delim)
37
39
} // namespace
38
40
39
41
std::optional<DummyDiagPublisher::Status> DummyDiagPublisher::convertStrToStatus (
40
- std::string & status_str)
42
+ const std::string & status_str)
41
43
{
42
44
static std::unordered_map<std::string, Status> const table = {
43
45
{" OK" , Status::OK}, {" Warn" , Status::WARN}, {" Error" , Status::ERROR}, {" Stale" , Status::STALE}};
@@ -144,6 +146,61 @@ rclcpp::NodeOptions override_options(rclcpp::NodeOptions options)
144
146
true );
145
147
}
146
148
149
+ rcl_interfaces::msg::SetParametersResult DummyDiagPublisher::onSetParams (
150
+ const std::vector<rclcpp::Parameter> & parameters)
151
+ {
152
+ rcl_interfaces::msg::SetParametersResult result;
153
+ result.successful = true ;
154
+
155
+ for (const auto & parameter : parameters) {
156
+ bool param_found = false ;
157
+ const auto & param_name = parameter.get_name ();
158
+
159
+ for (auto & diag : required_diags_) {
160
+ if (param_name == diag.name + std::string (" .status" )) {
161
+ param_found = true ;
162
+ auto new_status = convertStrToStatus (parameter.as_string ());
163
+ if (new_status) {
164
+ diag.status = *new_status;
165
+ RCLCPP_INFO (
166
+ this ->get_logger (), " Updated %s status to: %s" , diag.name .c_str (),
167
+ parameter.as_string ().c_str ());
168
+ } else {
169
+ result.successful = false ;
170
+ result.reason = " Invalid status value for: " + parameter.as_string ();
171
+ RCLCPP_WARN (
172
+ this ->get_logger (), " Invalid status value for %s: %s" , diag.name .c_str (),
173
+ parameter.as_string ().c_str ());
174
+ }
175
+ } else if (param_name == diag.name + std::string (" .is_active" )) {
176
+ param_found = true ;
177
+ try {
178
+ diag.is_active = parameter.as_bool ();
179
+ RCLCPP_INFO (
180
+ this ->get_logger (), " Updated %s is_active to: %s" , diag.name .c_str (),
181
+ diag.is_active ? " true" : " false" );
182
+ } catch (const rclcpp::ParameterTypeException & e) {
183
+ result.successful = false ;
184
+ result.reason = " Invalid is_active value for: " + parameter.as_string ();
185
+ RCLCPP_WARN (
186
+ this ->get_logger (), " Invalid is_active value for %s: %s" , diag.name .c_str (),
187
+ parameter.as_string ().c_str ());
188
+ }
189
+ }
190
+ }
191
+
192
+ if (!param_found) {
193
+ result.successful = false ;
194
+ result.reason = " Parameter not registered: " + parameter.get_name ();
195
+ RCLCPP_WARN (
196
+ this ->get_logger (), " Attempted to set unregistered parameter: %s" ,
197
+ parameter.get_name ().c_str ());
198
+ }
199
+ }
200
+
201
+ return result;
202
+ }
203
+
147
204
DummyDiagPublisher::DummyDiagPublisher (const rclcpp::NodeOptions & options)
148
205
: Node(" dummy_diag_publisher" , override_options(options))
149
206
@@ -164,6 +221,10 @@ DummyDiagPublisher::DummyDiagPublisher(const rclcpp::NodeOptions & options)
164
221
165
222
// Publisher
166
223
pub_ = create_publisher<diagnostic_msgs::msg::DiagnosticArray>(" /diagnostics" , rclcpp::QoS (1 ));
224
+
225
+ // Parameter Callback Handle
226
+ param_callback_handle_ = this ->add_on_set_parameters_callback (
227
+ std::bind (&DummyDiagPublisher::onSetParams, this , std::placeholders::_1));
167
228
}
168
229
169
230
#include < rclcpp_components/register_node_macro.hpp>
0 commit comments