Skip to content

Commit ae436b3

Browse files
feat(dummy_diag_publisher): update param setting (#9946)
* feat: update param setting Signed-off-by: TetsuKawa <kawaguchitnon@icloud.com> * style(pre-commit): autofix * modify: delete unnecessary include Signed-off-by: TetsuKawa <kawaguchitnon@icloud.com> --------- Signed-off-by: TetsuKawa <kawaguchitnon@icloud.com> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent 3edd7b5 commit ae436b3

File tree

3 files changed

+68
-4
lines changed

3 files changed

+68
-4
lines changed

system/dummy_diag_publisher/include/dummy_diag_publisher/dummy_diag_publisher_core.hpp

+5-1
Original file line numberDiff line numberDiff line change
@@ -60,9 +60,13 @@ class DummyDiagPublisher : public rclcpp::Node
6060
DummyDiagConfig config_;
6161

6262
RequiredDiags required_diags_;
63+
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr param_callback_handle_;
64+
6365
void loadRequiredDiags();
66+
rcl_interfaces::msg::SetParametersResult onSetParams(
67+
const std::vector<rclcpp::Parameter> & parameters);
6468

65-
std::optional<Status> convertStrToStatus(std::string & status_str);
69+
std::optional<Status> convertStrToStatus(const std::string & status_str);
6670
std::string convertStatusToStr(const Status & status);
6771
diagnostic_msgs::msg::DiagnosticStatus::_level_type convertStatusToLevel(const Status & status);
6872

system/dummy_diag_publisher/package.xml

+1-2
Original file line numberDiff line numberDiff line change
@@ -11,8 +11,7 @@
1111
<buildtool_depend>ament_cmake_auto</buildtool_depend>
1212
<buildtool_depend>autoware_cmake</buildtool_depend>
1313

14-
<depend>autoware_universe_utils</depend>
15-
<depend>diagnostic_updater</depend>
14+
<depend>diagnostic_msgs</depend>
1615
<depend>fmt</depend>
1716
<depend>rclcpp</depend>
1817
<depend>rclcpp_components</depend>

system/dummy_diag_publisher/src/dummy_diag_publisher_core.cpp

+62-1
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,8 @@
2222
#define FMT_HEADER_ONLY
2323
#include <fmt/format.h>
2424

25+
#include <sstream>
26+
2527
namespace
2628
{
2729
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)
3739
} // namespace
3840

3941
std::optional<DummyDiagPublisher::Status> DummyDiagPublisher::convertStrToStatus(
40-
std::string & status_str)
42+
const std::string & status_str)
4143
{
4244
static std::unordered_map<std::string, Status> const table = {
4345
{"OK", Status::OK}, {"Warn", Status::WARN}, {"Error", Status::ERROR}, {"Stale", Status::STALE}};
@@ -144,6 +146,61 @@ rclcpp::NodeOptions override_options(rclcpp::NodeOptions options)
144146
true);
145147
}
146148

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+
147204
DummyDiagPublisher::DummyDiagPublisher(const rclcpp::NodeOptions & options)
148205
: Node("dummy_diag_publisher", override_options(options))
149206

@@ -164,6 +221,10 @@ DummyDiagPublisher::DummyDiagPublisher(const rclcpp::NodeOptions & options)
164221

165222
// Publisher
166223
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));
167228
}
168229

169230
#include <rclcpp_components/register_node_macro.hpp>

0 commit comments

Comments
 (0)